-
Notifications
You must be signed in to change notification settings - Fork 124
Added wrapper for the move by command. #103
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: indigo-devel
Are you sure you want to change the base?
Changes from 4 commits
8e1a570
763c2e1
23fb05e
b7636d6
ecaf843
81d01cc
6e51598
ff19906
44353d1
a5dfd32
3ddc996
dc373e7
4c990b0
20c57aa
1cf2eec
15089f9
19b5ad0
90035f9
ee73812
ffed1bd
f92e45f
0aba6dd
75be564
035106c
b93ec8a
0051e05
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -870,6 +870,12 @@ class Ardrone3PilotingStateAltitudeChanged : public AbstractState | |
|
|
||
| }; // Ardrone3PilotingStateAltitudeChanged | ||
|
|
||
| // Relative move ended.\n Informs about the move that the drone managed to do and why it stopped. | ||
|
||
| class Ardrone3RelativeMoveEnded : public AbstractState | ||
| { | ||
|
|
||
| }; // Ardrone3RelativeMoveEnded | ||
|
|
||
|
|
||
| // Drones location changed.\n This event is meant to replace [PositionChanged](#1-4-4). | ||
| class Ardrone3PilotingStateGpsLocationChanged : public AbstractState | ||
|
|
@@ -1991,4 +1997,4 @@ class Ardrone3PROStateFeatures : public AbstractState | |
|
|
||
| } // namespace cb | ||
| } // namespace bebop_driver | ||
| #endif // BEBOP_AUTONOMY_AUTOGENERATED_ardrone3_STATE_CALLBACKS_H | ||
| #endif // BEBOP_AUTONOMY_AUTOGENERATED_ardrone3_STATE_CALLBACKS_H | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -32,4 +32,4 @@ gen = ParameterGenerator() | |
|
|
||
| {{/cfg_class}} | ||
|
|
||
| exit(gen.generate(PACKAGE, "bebop_driver_nodelet", "Bebop{{project}}")) | ||
| exit(gen.generate(PACKAGE, "bebop_driver_nodelet", "Bebop{{project}}")) | ||
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -549,6 +549,20 @@ void Bebop::Move(const double &roll, const double &pitch, const double &gaz_spee | |
| } | ||
| } | ||
|
|
||
|
|
||
| void Bebop::MoveBy(const float& dX, const float& dY, const float& dZ, const float& dPsi) | ||
|
||
| { | ||
| ThrowOnInternalError("MoveBy failure"); | ||
|
|
||
| ThrowOnCtrlError( | ||
| device_controller_ptr_->aRDrone3->sendPilotingMoveBy( | ||
| device_controller_ptr_->aRDrone3, | ||
| static_cast<float>(dX), | ||
| static_cast<float>(dY), | ||
| static_cast<float>(dZ), | ||
| static_cast<float>(dPsi))); | ||
| } | ||
|
|
||
| // in degrees | ||
| void Bebop::MoveCamera(const double &tilt, const double &pan) | ||
| { | ||
|
|
@@ -607,6 +621,18 @@ void Bebop::TakeSnapshot() | |
| device_controller_ptr_->aRDrone3)); | ||
| } | ||
|
|
||
| /** | ||
| * @brief Set the format of the taken pictures | ||
| * @param format 0: Raw image, 1: 4:3 jpeg photo, 2: 16:9 snapshot from camera, 3: jpeg fisheye image only | ||
| */ | ||
| void Bebop::SetPictureFormat(const int& format) | ||
| { | ||
| ThrowOnInternalError("Failed to set picture format"); | ||
| ThrowOnCtrlError( | ||
| device_controller_ptr_->aRDrone3->sendPictureSettingsPictureFormatSelection( | ||
| device_controller_ptr_->aRDrone3, (eARCOMMANDS_ARDRONE3_PICTURESETTINGS_PICTUREFORMATSELECTION_TYPE)format)); | ||
| } | ||
|
|
||
| void Bebop::SetExposure(const float& exposure) | ||
| { | ||
| ThrowOnInternalError("Failed to set exposure"); | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -31,6 +31,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI | |
| #include <tf2_geometry_msgs/tf2_geometry_msgs.h> | ||
| #include <tf2_ros/transform_broadcaster.h> | ||
| #include <sensor_msgs/NavSatFix.h> | ||
| #include <std_msgs/UInt8.h> | ||
|
|
||
| #include <boost/bind.hpp> | ||
| #include <boost/make_shared.hpp> | ||
|
|
@@ -133,6 +134,7 @@ void BebopDriverNodelet::onInit() | |
| } | ||
|
|
||
| cmd_vel_sub_ = nh.subscribe("cmd_vel", 1, &BebopDriverNodelet::CmdVelCallback, this); | ||
| cmd_move_by = nh.subscribe("cmd_move_by", 1, &BebopDriverNodelet::CmdMoveByCallback, this); | ||
| camera_move_sub_ = nh.subscribe("camera_control", 1, &BebopDriverNodelet::CameraMoveCallback, this); | ||
| takeoff_sub_ = nh.subscribe("takeoff", 1, &BebopDriverNodelet::TakeoffCallback, this); | ||
| land_sub_ = nh.subscribe("land", 1, &BebopDriverNodelet::LandCallback, this); | ||
|
|
@@ -144,6 +146,7 @@ void BebopDriverNodelet::onInit() | |
| stop_autoflight_sub_ = nh.subscribe("autoflight/stop", 1, &BebopDriverNodelet::StopAutonomousFlightCallback, this); | ||
| animation_sub_ = nh.subscribe("flip", 1, &BebopDriverNodelet::FlipAnimationCallback, this); | ||
| snapshot_sub_ = nh.subscribe("snapshot", 10, &BebopDriverNodelet::TakeSnapshotCallback, this); | ||
| setpictureformat_sub = nh.subscribe("set_picture_format", 1, &BebopDriverNodelet::SetPictureFormatCallback, this); | ||
| exposure_sub_ = nh.subscribe("set_exposure", 10, &BebopDriverNodelet::SetExposureCallback, this); | ||
| toggle_recording_sub_ = nh.subscribe("record", 10, &BebopDriverNodelet::ToggleRecordingCallback, this); | ||
|
|
||
|
|
@@ -232,6 +235,23 @@ void BebopDriverNodelet::CmdVelCallback(const geometry_msgs::TwistConstPtr& twis | |
| } | ||
| } | ||
|
|
||
| void BebopDriverNodelet::CmdMoveByCallback(const geometry_msgs::TwistConstPtr& twist_ptr) | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Please
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I'm not sure, if I understood your comment correctly. Pleas let me know, if it's the case. |
||
| { | ||
| try | ||
| { | ||
| const geometry_msgs::Twist& bebop_twist_ = *twist_ptr; | ||
|
|
||
| bebop_ptr_->MoveBy(bebop_twist_.linear.x, | ||
| bebop_twist_.linear.y, | ||
| bebop_twist_.linear.z, | ||
| bebop_twist_.angular.z); | ||
| } | ||
| catch (const std::runtime_error& e) | ||
| { | ||
| ROS_ERROR_STREAM(e.what()); | ||
| } | ||
| } | ||
|
|
||
| void BebopDriverNodelet::TakeoffCallback(const std_msgs::EmptyConstPtr& empty_ptr) | ||
| { | ||
| try | ||
|
|
@@ -392,6 +412,19 @@ void BebopDriverNodelet::TakeSnapshotCallback(const std_msgs::EmptyConstPtr &emp | |
| } | ||
| } | ||
|
|
||
| void BebopDriverNodelet::SetPictureFormatCallback(const std_msgs::UInt8ConstPtr& format_ptr) | ||
| { | ||
| try | ||
| { | ||
| ROS_INFO("Setting picture format to %f", format_ptr->data); | ||
|
||
| bebop_ptr_->SetPictureFormat(format_ptr->data); | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. What if |
||
| } | ||
| catch (const std::runtime_error& e) | ||
| { | ||
| ROS_ERROR_STREAM(e.what()); | ||
| } | ||
| } | ||
|
|
||
| void BebopDriverNodelet::SetExposureCallback(const std_msgs::Float32ConstPtr& exposure_ptr) | ||
| { | ||
| try | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -133,7 +133,7 @@ bool VideoDecoder::ReallocateBuffers() | |
| boost::lexical_cast<std::string>(codec_ctx_ptr_->width) + | ||
| " x " + boost::lexical_cast<std::string>(codec_ctx_ptr_->width)); | ||
|
|
||
| const uint32_t num_bytes = avpicture_get_size(PIX_FMT_RGB24, codec_ctx_ptr_->width, codec_ctx_ptr_->width); | ||
| const uint32_t num_bytes = avpicture_get_size(AV_PIX_FMT_RGB24, codec_ctx_ptr_->width, codec_ctx_ptr_->width); | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Could you please explain this change?
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The current ffmpeg uses AV_PIX_FMT_RGB24. Older versions of ffmpeg provide PIX_FMT_RGB24. |
||
| frame_rgb_ptr_ = av_frame_alloc(); | ||
|
|
||
| ThrowOnCondition(!frame_rgb_ptr_, "Can not allocate memory for frames!"); | ||
|
|
@@ -143,12 +143,12 @@ bool VideoDecoder::ReallocateBuffers() | |
| std::string("Can not allocate memory for the buffer: ") + | ||
| boost::lexical_cast<std::string>(num_bytes)); | ||
| ThrowOnCondition(0 == avpicture_fill( | ||
| reinterpret_cast<AVPicture*>(frame_rgb_ptr_), frame_rgb_raw_ptr_, PIX_FMT_RGB24, | ||
| reinterpret_cast<AVPicture*>(frame_rgb_ptr_), frame_rgb_raw_ptr_, AV_PIX_FMT_RGB24, | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Same here. |
||
| codec_ctx_ptr_->width, codec_ctx_ptr_->height), | ||
| "Failed to initialize the picture data structure."); | ||
|
|
||
| img_convert_ctx_ptr_ = sws_getContext(codec_ctx_ptr_->width, codec_ctx_ptr_->height, codec_ctx_ptr_->pix_fmt, | ||
| codec_ctx_ptr_->width, codec_ctx_ptr_->height, PIX_FMT_RGB24, | ||
| codec_ctx_ptr_->width, codec_ctx_ptr_->height, AV_PIX_FMT_RGB24, | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Same here. |
||
| SWS_FAST_BILINEAR, NULL, NULL, NULL); | ||
| } | ||
| catch (const std::runtime_error& e) | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Please revert back changes to this file.