mavros version selection as cmake flag
This commit is contained in:
parent
2d6d5d0d28
commit
ffbe4569cc
|
@ -6,9 +6,9 @@ if(UNIX)
|
|||
endif()
|
||||
|
||||
if(SIM)
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DSIMULATION=1")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DSIMULATION=1 -DMAVROSKINETIC=1")
|
||||
else()
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DSIMULATION=0")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DSIMULATION=0 -DMAVROSKINETIC=1")
|
||||
endif()
|
||||
## Find catkin macros and libraries
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
|
|
|
@ -401,7 +401,11 @@ int buzzuav_arm(buzzvm_t vm)
|
|||
/ Buzz closure to arm
|
||||
/---------------------------------------*/
|
||||
{
|
||||
#ifdef MAVROSKINETIC
|
||||
cur_cmd = mavros_msgs::CommandCode::COMPONENT_ARM_DISARM;
|
||||
#else
|
||||
cur_cmd = mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM;
|
||||
#endif
|
||||
printf(" Buzz requested Arm \n");
|
||||
buzz_cmd = COMMAND_ARM;
|
||||
return buzzvm_ret0(vm);
|
||||
|
@ -412,7 +416,11 @@ int buzzuav_disarm(buzzvm_t vm)
|
|||
/ Buzz closure to disarm
|
||||
/---------------------------------------*/
|
||||
{
|
||||
#ifdef MAVROSKINETIC
|
||||
cur_cmd = mavros_msgs::CommandCode::COMPONENT_ARM_DISARM + 1;
|
||||
#else
|
||||
cur_cmd = mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM + 1;
|
||||
#endif
|
||||
printf(" Buzz requested Disarm \n");
|
||||
buzz_cmd = COMMAND_DISARM;
|
||||
return buzzvm_ret0(vm);
|
||||
|
|
|
@ -780,7 +780,11 @@ script
|
|||
}
|
||||
else
|
||||
ROS_ERROR("Failed to call service from flight controller");
|
||||
#ifdef MAVROSKINETIC
|
||||
cmd_srv.request.command = mavros_msgs::CommandCode::MISSION_START;
|
||||
#else
|
||||
cmd_srv.request.command = mavros_msgs::CommandCode::CMD_MISSION_START;
|
||||
#endif
|
||||
if (mav_client.call(cmd_srv))
|
||||
{
|
||||
ROS_INFO("Reply: %ld", (long int)cmd_srv.response.success);
|
||||
|
@ -818,7 +822,11 @@ script
|
|||
cmd_srv.request.param2 = gimbal[1];
|
||||
cmd_srv.request.param3 = gimbal[2];
|
||||
cmd_srv.request.param4 = gimbal[3];
|
||||
#ifdef MAVROSKINETIC
|
||||
cmd_srv.request.command = mavros_msgs::CommandCode::DO_MOUNT_CONTROL;
|
||||
#else
|
||||
cmd_srv.request.command = mavros_msgs::CommandCode::CMD_DO_MOUNT_CONTROL;
|
||||
#endif
|
||||
if (mav_client.call(cmd_srv))
|
||||
{
|
||||
ROS_INFO("Reply: %ld", (long int)cmd_srv.response.success);
|
||||
|
@ -1220,8 +1228,13 @@ bool roscontroller::rc_callback(mavros_msgs::CommandLong::Request& req, mavros_m
|
|||
buzzuav_closures::rc_call(rc_cmd);
|
||||
res.success = true;
|
||||
break;
|
||||
#ifdef MAVROSKINETIC
|
||||
case mavros_msgs::CommandCode::COMPONENT_ARM_DISARM:
|
||||
rc_cmd = mavros_msgs::CommandCode::COMPONENT_ARM_DISARM;
|
||||
#else
|
||||
case mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM:
|
||||
rc_cmd = mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM;
|
||||
#endif
|
||||
armstate = req.param1;
|
||||
if (armstate)
|
||||
{
|
||||
|
@ -1249,10 +1262,18 @@ bool roscontroller::rc_callback(mavros_msgs::CommandLong::Request& req, mavros_m
|
|||
buzzuav_closures::rc_call(rc_cmd);
|
||||
res.success = true;
|
||||
break;
|
||||
#ifdef MAVROSKINETIC
|
||||
case mavros_msgs::CommandCode::DO_MOUNT_CONTROL:
|
||||
#else
|
||||
case mavros_msgs::CommandCode::CMD_DO_MOUNT_CONTROL:
|
||||
#endif
|
||||
ROS_INFO("RC_Call: Gimbal!!!! ");
|
||||
buzzuav_closures::rc_set_gimbal(req.param1, req.param2, req.param3, req.param4, req.param5);
|
||||
#ifdef MAVROSKINETIC
|
||||
rc_cmd = mavros_msgs::CommandCode::DO_MOUNT_CONTROL;
|
||||
#else
|
||||
rc_cmd = mavros_msgs::CommandCode::CMD_DO_MOUNT_CONTROL;
|
||||
#endif
|
||||
buzzuav_closures::rc_call(rc_cmd);
|
||||
res.success = true;
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue