initial commit, fix compile issues in kinetic, compatible with new mavros headers

This commit is contained in:
David St-Onge 2018-05-29 19:04:39 +00:00
parent a99d2a6496
commit 44280c3d91
2 changed files with 8 additions and 8 deletions

View File

@ -400,7 +400,7 @@ int buzzuav_arm(buzzvm_t vm)
/ Buzz closure to arm
/---------------------------------------*/
{
cur_cmd = mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM;
cur_cmd = mavros_msgs::CommandCode::COMPONENT_ARM_DISARM;
printf(" Buzz requested Arm \n");
buzz_cmd = COMMAND_ARM;
return buzzvm_ret0(vm);
@ -411,7 +411,7 @@ int buzzuav_disarm(buzzvm_t vm)
/ Buzz closure to disarm
/---------------------------------------*/
{
cur_cmd = mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM + 1;
cur_cmd = mavros_msgs::CommandCode::COMPONENT_ARM_DISARM + 1;
printf(" Buzz requested Disarm \n");
buzz_cmd = COMMAND_DISARM;
return buzzvm_ret0(vm);

View File

@ -682,7 +682,7 @@ script
}
else
ROS_ERROR("Failed to call service from flight controller");
cmd_srv.request.command = mavros_msgs::CommandCode::CMD_MISSION_START;
cmd_srv.request.command = mavros_msgs::CommandCode::MISSION_START;
if (mav_client.call(cmd_srv))
{
ROS_INFO("Reply: %ld", (long int)cmd_srv.response.success);
@ -720,7 +720,7 @@ script
cmd_srv.request.param2 = gimbal[1];
cmd_srv.request.param3 = gimbal[2];
cmd_srv.request.param4 = gimbal[3];
cmd_srv.request.command = mavros_msgs::CommandCode::CMD_DO_MOUNT_CONTROL;
cmd_srv.request.command = mavros_msgs::CommandCode::DO_MOUNT_CONTROL;
if (mav_client.call(cmd_srv))
{
ROS_INFO("Reply: %ld", (long int)cmd_srv.response.success);
@ -1094,8 +1094,8 @@ bool roscontroller::rc_callback(mavros_msgs::CommandLong::Request& req, mavros_m
buzzuav_closures::rc_call(rc_cmd);
res.success = true;
break;
case mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM:
rc_cmd = mavros_msgs::CommandCode::CMD_COMPONENT_ARM_DISARM;
case mavros_msgs::CommandCode::COMPONENT_ARM_DISARM:
rc_cmd = mavros_msgs::CommandCode::COMPONENT_ARM_DISARM;
armstate = req.param1;
if (armstate)
{
@ -1123,10 +1123,10 @@ bool roscontroller::rc_callback(mavros_msgs::CommandLong::Request& req, mavros_m
buzzuav_closures::rc_call(rc_cmd);
res.success = true;
break;
case mavros_msgs::CommandCode::CMD_DO_MOUNT_CONTROL:
case mavros_msgs::CommandCode::DO_MOUNT_CONTROL:
ROS_INFO("RC_Call: Gimbal!!!! ");
buzzuav_closures::rc_set_gimbal(req.param1, req.param2, req.param3, req.param4, req.param5);
rc_cmd = mavros_msgs::CommandCode::CMD_DO_MOUNT_CONTROL;
rc_cmd = mavros_msgs::CommandCode::DO_MOUNT_CONTROL;
buzzuav_closures::rc_call(rc_cmd);
res.success = true;
break;