Skip to content
Permalink

Comparing changes

Choose two branches to see what’s changed or to start a new pull request. If you need to, you can also or learn more about diff comparisons.

Open a pull request

Create a new pull request by comparing changes across two branches. If you need to, you can also . Learn more about diff comparisons here.
base repository: dji-sdk/Onboard-SDK-ROS
Failed to load repositories. Confirm that selected base ref is valid, then try again.
Loading
base: master
Choose a base ref
...
head repository: umdlife/Onboard-SDK-ROS
Failed to load repositories. Confirm that selected head ref is valid, then try again.
Loading
compare: master_umd
Choose a head ref
Able to merge. These branches can be automatically merged.
Loading
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -148,6 +148,7 @@ add_service_files(
SetCurrentAircraftLocAsHomePoint.srv
SetHomePoint.srv
SetupCameraH264.srv
ChangeH264Source.srv
SetAvoidEnable.srv
GetAvoidEnable.srv
InitWaypointV2Setting.srv
34 changes: 32 additions & 2 deletions include/dji_osdk_ros/dji_vehicle_node.h
Original file line number Diff line number Diff line change
@@ -35,6 +35,8 @@

#include <dji_osdk_ros/vehicle_wrapper.h>
#include <dji_osdk_ros/common_type.h>
#include <umd_rtsp/rtsp_streamer.hpp>
#include <umd_rtsp/utils.hpp>

#include <memory>
#include <string>
@@ -45,6 +47,7 @@
#include <geometry_msgs/QuaternionStamped.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/Joy.h>
@@ -134,6 +137,7 @@
#ifdef ADVANCED_SENSING
#include <dji_osdk_ros/SetupCameraH264.h>
#include <dji_osdk_ros/SetupCameraStream.h>
#include <dji_osdk_ros/ChangeH264Source.h>
#include <dji_osdk_ros/Stereo240pSubscription.h>
#include <dji_osdk_ros/StereoDepthSubscription.h>
#include <dji_osdk_ros/StereoVGASubscription.h>
@@ -148,6 +152,7 @@
#include <dji_osdk_ros/VOPosition.h>
#include <dji_osdk_ros/FCTimeInUTC.h>
#include <dji_osdk_ros/GPSUTC.h>
#include <dji_osdk_ros/JoystickParams.h>

//waypointV2.0
#include <dji_osdk_ros/WaypointV2.h>
@@ -176,6 +181,7 @@
#define RAD2DEG(RAD) ((RAD) * (180.0) / (C_PI))
const int WAIT_TIMEOUT = 10;
const int FLIGHT_CONTROL_WAIT_TIMEOUT = 1;
const float POSITION_CONTROL_TIMEOUT = 0.05; // ensure minimum rate of 20hz of the position command (30hz being expected value)

// Declaration
namespace dji_osdk_ros
@@ -186,7 +192,7 @@ namespace dji_osdk_ros
class VehicleNode
{
public:
VehicleNode();
VehicleNode(ros::NodeHandle& nh, ros::NodeHandle& nh_private);
VehicleNode(int test);

~VehicleNode();
@@ -250,10 +256,12 @@ namespace dji_osdk_ros
#ifdef ADVANCED_SENSING
ros::ServiceServer setup_camera_stream_server_;
ros::ServiceServer setup_camera_h264_server_;
ros::ServiceServer change_h264_source_server_;
ros::ServiceServer subscribe_stereo_240p_server_;
ros::ServiceServer subscribe_stereo_depth_server_;
ros::ServiceServer subscribe_stereo_vga_server_;
ros::ServiceServer get_m300_stereo_params_server_;
std::string gstreamer_writer_pipeline_;
#endif
/*! for mission */
ros::ServiceServer waypoint_upload_server_;
@@ -319,6 +327,12 @@ namespace dji_osdk_ros
ros::Publisher time_sync_gps_utc_publisher_;
ros::Publisher time_sync_fc_utc_publisher_;
ros::Publisher time_sync_pps_source_publisher_;
// Subscribers
ros::Subscriber flight_control_sub_;
ros::Subscriber flight_control_velocity_yawrate_sub_;
ros::Subscriber flight_control_position_sub_;
ros::Subscriber gimbal_incremental_control_sub_;


//advanced sensing
#ifdef ADVANCED_SENSING
@@ -344,6 +358,9 @@ namespace dji_osdk_ros
dji_osdk_ros::GetDroneType::Response &response);
/*! for flight control */
bool taskCtrlCallback(FlightTaskControl::Request& request, FlightTaskControl::Response& response);
void flightControlSetpointCallback(const sensor_msgs::Joy::ConstPtr& msg);
void flightControlVxVyVzYawrateCallback(const sensor_msgs::Joy::ConstPtr& msg);
void flightControlPosCallback(const sensor_msgs::Joy::ConstPtr& msg);
bool setJoystickModeCallback(SetJoystickMode::Request& request, SetJoystickMode::Response& response);
bool JoystickActionCallback(JoystickAction::Request& request, JoystickAction::Response& response);
bool setGoHomeAltitudeCallback(SetGoHomeAltitude::Request& request, SetGoHomeAltitude::Response& response);
@@ -362,7 +379,8 @@ namespace dji_osdk_ros
bool emergencyBrakeCallback(EmergencyBrake::Request& request, EmergencyBrake::Response& response);
/*! for gimbal control */
bool gimbalCtrlCallback(GimbalAction::Request& request, GimbalAction::Response& response);
/*! for camera conrol */
/*! for camera incremental control */
void gimbalIncrementCtrlCallback(const dji_osdk_ros::Gimbal::ConstPtr& msg);
bool cameraSetEVCallback(CameraEV::Request& request, CameraEV::Response& response);
bool cameraSetShutterSpeedCallback(CameraShutterSpeed::Request& request, CameraShutterSpeed::Response& response);
bool cameraSetApertureCallback(CameraAperture::Request& request, CameraAperture::Response& response);
@@ -403,6 +421,8 @@ namespace dji_osdk_ros
dji_osdk_ros::SetupCameraStream::Response& response);
bool setupCameraH264Callback(dji_osdk_ros::SetupCameraH264::Request& request,
dji_osdk_ros::SetupCameraH264::Response& response);
bool changeH264SourceCallback(dji_osdk_ros::ChangeH264Source::Request& request,
dji_osdk_ros::ChangeH264Source::Response& response);
//! stereo image service callback
bool stereo240pSubscriptionCallback(dji_osdk_ros::Stereo240pSubscription::Request& request,
dji_osdk_ros::Stereo240pSubscription::Response& response);
@@ -474,6 +494,7 @@ namespace dji_osdk_ros

private:
ros::NodeHandle nh_;
ros::NodeHandle nh_private_;
VehicleWrapper* ptr_wrapper_;
TelemetryType telemetry_from_fc_;

@@ -489,6 +510,10 @@ namespace dji_osdk_ros
std::string app_bundle_id_; // reserved
bool user_select_broadcast_;
bool align_time_with_FC_;
bool enable_stream_;
std::string frame_id;
std::string child_frame_id;
double attitude_x, attitude_y, attitude_z, attitude_w;

AlignStatus curr_align_state_;
ros::Time base_time_;
@@ -503,6 +528,9 @@ namespace dji_osdk_ros
bool stereo_subscription_success;
bool stereo_vga_subscription_success;

ros::Time lastReceivedPosCommandTime;
umd_rtsp::RTSPStreamer rtsp_streamer_;

std::vector<DJIWaypointV2Action> actions;

//! data broadcast callback
@@ -559,6 +587,8 @@ namespace dji_osdk_ros
static void publishMainCameraImage(CameraRGBImage rgbImg, void* userData);
static void publishFPVCameraImage(CameraRGBImage rgbImg, void* userData);
static void publishCameraH264(uint8_t* buf, int bufLen, void* userData);
static void streamCamera(CameraRGBImage rgbImg, void* userData);

static void publish240pStereoImage(Vehicle* vehicle,
RecvContainer recvFrame,
DJI::OSDK::UserData userData);
6 changes: 5 additions & 1 deletion include/dji_osdk_ros/vehicle_wrapper.h
Original file line number Diff line number Diff line change
@@ -127,6 +127,9 @@ namespace dji_osdk_ros
bool moveByPositionOffset(const JoystickCommand &JoystickCommand,int timeout,
float posThresholdInM = 0.8,float yawThresholdInDeg = 1.0);
void velocityAndYawRateCtrl(const JoystickCommand &JoystickCommand, int timeMs);
void velocityAndYawRateCtrl(const JoystickCommand &JoystickCommand);
void genericCtrl(const JoystickCommand &JoystickCommand, uint8_t flag);
bool localPosCtrl(const JoystickCommand &poseCommand);
bool setJoystickMode(const JoystickMode &joystickMode);
bool JoystickAction(const JoystickCommand &JoystickCommand);
bool obtainReleaseCtrlAuthority(bool enableObtain, int timeout);
@@ -178,6 +181,7 @@ namespace dji_osdk_ros
/*! H264 */
bool startH264Stream(LiveView::LiveViewCameraPosition pos, H264Callback cb, void *userData);
bool stopH264Stream(LiveView::LiveViewCameraPosition pos);
bool changeH264Source(LiveView::LiveViewCameraPosition pos, LiveView::LiveViewCameraSource source);
void setAcmDevicePath(const std::string& acm_path);

/*! @brief subscribe to QVGA (240x320) stereo images at 20 fps
@@ -255,6 +259,7 @@ namespace dji_osdk_ros
UserData userData);
Version::FirmWare getFwVersion() const;
char* getHwVersion() const;
Vector3f quaternionToEulerAngle(const Telemetry::Quaternion& quat);

private:
uint32_t timeout_;
@@ -272,7 +277,6 @@ namespace dji_osdk_ros
Vector3f vector3FSub(const Vector3f& vectorA,const Vector3f& vectorB);
float32_t vectorNorm(Vector3f v);
void horizCommandLimit(float speedFactor, float& commandX,float& commandY);
Vector3f quaternionToEulerAngle(const Telemetry::Quaternion& quat);
static Vector3f localOffsetFromGpsAndFusedHeightOffset(const Telemetry::GPSFused& target,
const Telemetry::GPSFused& origin,
const float32_t& targetHeight,
8 changes: 8 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -61,6 +61,8 @@
<build_depend>actionlib_msgs</build_depend>
<build_depend>nmea_msgs</build_depend>
<build_depend>message_filters</build_depend>
<build_depend>tf2</build_depend>
<build_depend>tf2_ros</build_depend>

<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
@@ -72,7 +74,13 @@
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>
<exec_depend>message_filters</exec_depend>
<exec_depend>tf2</exec_depend>
<exec_depend>tf2_ros</exec_depend>

<depend>umd_rtsp</depend>
<depend>umd_http</depend>
<depend>nlohmann_json</depend>

<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
2 changes: 2 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,2 +1,4 @@
add_compile_options(-std=c++17)

add_subdirectory(dji_osdk_ros)
add_subdirectory(dji_osdk_ros_obsoleted)
11 changes: 11 additions & 0 deletions src/dji_osdk_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -7,6 +7,9 @@ if(OPEN_CV_3_3_0_INSTALLED AND FOUND_OPENCV_VIZ)
add_definitions(-DOPEN_CV_INSTALLED)
endif()

find_package(PkgConfig REQUIRED)
pkg_check_modules(CURLPP REQUIRED curlpp)

FOREACH(EXAMPLE ${EXAMPLES})
GET_FILENAME_COMPONENT(MY_TARGET "${EXAMPLE}" NAME_WE)
ADD_EXECUTABLE(${MY_TARGET} ${EXAMPLE})
@@ -18,6 +21,8 @@ FOREACH(EXAMPLE ${EXAMPLES})

TARGET_LINK_LIBRARIES(${MY_TARGET}
${PROJECT_NAME}
-lcurlpp
-lcurl
)

INSTALL(TARGETS ${MY_TARGET}
@@ -26,3 +31,9 @@ FOREACH(EXAMPLE ${EXAMPLES})
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
ENDFOREACH()

install(TARGETS dji_osdk_ros
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
Loading