Skip to content
Open
Show file tree
Hide file tree
Changes from 4 commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
8e1a570
Added cmd_move_by command.
AndreasAZiegler Mar 31, 2017
763c2e1
Merge branch 'indigo-devel' of https://github.com/AndreasAZiegler/beb…
AndreasAZiegler Mar 31, 2017
23fb05e
Removed Arch Linux specific python changes.
AndreasAZiegler Mar 31, 2017
b7636d6
Added SetPictureFormat
AndreasAZiegler Apr 11, 2017
ecaf843
Add maintainers to readme, docs and manifest (closes #115)
mani-monaj Jun 13, 2017
81d01cc
Remove the Release build flag from the documentation
mani-monaj Jun 27, 2017
6e51598
Added cmd_move_by command.
AndreasAZiegler Mar 31, 2017
ff19906
Removed Arch Linux specific python changes.
AndreasAZiegler Mar 31, 2017
44353d1
Reverted changes to autogenerated file.
AndreasAZiegler Jul 12, 2017
a5dfd32
Revert changes in an autogenerated file.
AndreasAZiegler Jul 12, 2017
3ddc996
Reverted changes in a template.
AndreasAZiegler Jul 12, 2017
dc373e7
Changed floats to doubles in MoveBy signature.
AndreasAZiegler Jul 12, 2017
4c990b0
Removed blank line.
AndreasAZiegler Jul 12, 2017
20c57aa
Corrcted type for unit8_t.
AndreasAZiegler Jul 12, 2017
1cf2eec
Added entry in the contribute list.
AndreasAZiegler Jul 12, 2017
15089f9
Added documentation for the command move by.
AndreasAZiegler Jul 12, 2017
19b5ad0
Added documentation of the set_picture_format command.
AndreasAZiegler Jul 12, 2017
90035f9
Adapted entry in the contribute list.
AndreasAZiegler Jul 12, 2017
ee73812
Added unit test for move by command.
AndreasAZiegler Jul 13, 2017
ffed1bd
Adapted generate script to use the current (3.12.6) message definitions.
AndreasAZiegler Jul 17, 2017
f92e45f
Updated autogenerated files with the adapted gnerate python script.
AndreasAZiegler Jul 17, 2017
0aba6dd
Revert "Updated autogenerated files with the adapted gnerate python s…
AndreasAZiegler Jul 18, 2017
75be564
Revert "Adapted generate script to use the current (3.12.6) message d…
AndreasAZiegler Jul 18, 2017
035106c
Moved state definitions into test class as they will be used by multi…
AndreasAZiegler Jul 18, 2017
b93ec8a
Removed StopBebop() at some places. Added speed check after end of a …
AndreasAZiegler Jul 18, 2017
0051e05
Adapted values in PilotingWithMoveBy unit test. PilotingWithMoveBy un…
AndreasAZiegler Jul 18, 2017
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion bebop_driver/cfg/autogenerated/BebopArdrone3.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -135,4 +135,4 @@ gpssettings_group_gen.add("GPSSettingsHomeTypeType", int_t, 0, "The type of the
gpssettings_group_gen.add("GPSSettingsReturnHomeDelayDelay", int_t, 0, "Delay in second", 0 , 0, 120)


exit(gen.generate(PACKAGE, "bebop_driver_nodelet", "BebopArdrone3"))
exit(gen.generate(PACKAGE, "bebop_driver_nodelet", "BebopArdrone3"))
Copy link
Member

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.

Original file line number Diff line number Diff line change
Expand Up @@ -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.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you need the following class to be part of this file? Unfortunately this file is auto-generated and will be overwritten by subsequent SDK updates.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, shouldn't be needed. I guess I was not enough careful while adding files.

class Ardrone3RelativeMoveEnded : public AbstractState
{

}; // Ardrone3RelativeMoveEnded


// Drones location changed.\n This event is meant to replace [PositionChanged](#1-4-4).
class Ardrone3PilotingStateGpsLocationChanged : public AbstractState
Expand Down Expand Up @@ -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
7 changes: 7 additions & 0 deletions bebop_driver/include/bebop_driver/bebop.h
Original file line number Diff line number Diff line change
Expand Up @@ -170,9 +170,16 @@ class Bebop

// -1..1
void Move(const double& roll, const double& pitch, const double& gaz_speed, const double& yaw_speed);
void MoveBy(const float& dX, const float& dY, const float& dZ, const float& dPsi);
void MoveCamera(const double& tilt, const double& pan);

void TakeSnapshot();

/**
* @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 SetPictureFormat(const int& format);
// exposure should be between -3.0 and +3.0
void SetExposure(const float& exposure);
// true: start, false: stop
Expand Down
4 changes: 4 additions & 0 deletions bebop_driver/include/bebop_driver/bebop_driver_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,7 @@ class BebopDriverNodelet : public nodelet::Nodelet
geometry_msgs::Twist prev_camera_twist_;

ros::Subscriber cmd_vel_sub_;
ros::Subscriber cmd_move_by;
ros::Subscriber camera_move_sub_;
ros::Subscriber takeoff_sub_;
ros::Subscriber land_sub_;
Expand All @@ -122,6 +123,7 @@ class BebopDriverNodelet : public nodelet::Nodelet
ros::Subscriber stop_autoflight_sub_;
ros::Subscriber animation_sub_;
ros::Subscriber snapshot_sub_;
ros::Subscriber setpictureformat_sub;
ros::Subscriber exposure_sub_;
ros::Subscriber toggle_recording_sub_;

Expand Down Expand Up @@ -151,6 +153,7 @@ class BebopDriverNodelet : public nodelet::Nodelet
void AuxThread();

void CmdVelCallback(const geometry_msgs::TwistConstPtr& twist_ptr);
void CmdMoveByCallback(const geometry_msgs::TwistConstPtr& twist_ptr);
void CameraMoveCallback(const geometry_msgs::TwistConstPtr& twist_ptr);
void TakeoffCallback(const std_msgs::EmptyConstPtr& empty_ptr);
void LandCallback(const std_msgs::EmptyConstPtr& empty_ptr);
Expand All @@ -162,6 +165,7 @@ class BebopDriverNodelet : public nodelet::Nodelet
void StopAutonomousFlightCallback(const std_msgs::EmptyConstPtr& empty_ptr);
void FlipAnimationCallback(const std_msgs::UInt8ConstPtr& animid_ptr);
void TakeSnapshotCallback(const std_msgs::EmptyConstPtr& empty_ptr);
void SetPictureFormatCallback(const std_msgs::UInt8ConstPtr &format_ptr);
void SetExposureCallback(const std_msgs::Float32ConstPtr& exposure_ptr);
void ToggleRecordingCallback(const std_msgs::BoolConstPtr& toggle_ptr);

Expand Down
2 changes: 1 addition & 1 deletion bebop_driver/scripts/meta/templates/cfg.mustache
Original file line number Diff line number Diff line change
Expand Up @@ -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}}"))
Copy link
Member

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.

26 changes: 26 additions & 0 deletions bebop_driver/src/bebop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please change float to double in the signature since the twist message fields (that you pass here) are all doubles.

{
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)
{
Expand Down Expand Up @@ -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");
Expand Down
33 changes: 33 additions & 0 deletions bebop_driver/src/bebop_driver_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down Expand Up @@ -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);
Expand All @@ -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);

Expand Down Expand Up @@ -232,6 +235,23 @@ void BebopDriverNodelet::CmdVelCallback(const geometry_msgs::TwistConstPtr& twis
}
}

void BebopDriverNodelet::CmdMoveByCallback(const geometry_msgs::TwistConstPtr& twist_ptr)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please lint this function (indents, extra blank lines).

Copy link
Author

Choose a reason for hiding this comment

The 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
Expand Down Expand Up @@ -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);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think %f is correct here, since the input is of type uint8_t. Please fix.

bebop_ptr_->SetPictureFormat(format_ptr->data);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What if format_ptr->data is not set to a value supported by SetPictureFormat? Please add a guard (or a warning) against this.

}
catch (const std::runtime_error& e)
{
ROS_ERROR_STREAM(e.what());
}
}

void BebopDriverNodelet::SetExposureCallback(const std_msgs::Float32ConstPtr& exposure_ptr)
{
try
Expand Down
6 changes: 3 additions & 3 deletions bebop_driver/src/bebop_video_decoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you please explain this change?

Copy link
Author

Choose a reason for hiding this comment

The 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!");
Expand All @@ -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,
Copy link
Member

Choose a reason for hiding this comment

The 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,
Copy link
Member

Choose a reason for hiding this comment

The 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)
Expand Down