Mission: support do-mount-control
This commit is contained in:
parent
e1abdadc06
commit
f6021010c5
@ -604,8 +604,13 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL: // MAV ID: 203
|
||||
// command takes no parameters
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
|
||||
// these commands takes no parameters
|
||||
cmd.content.mount_control.pitch = packet.param1;
|
||||
cmd.content.mount_control.roll = packet.param2;
|
||||
cmd.content.mount_control.yaw = packet.param3;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
|
||||
@ -877,10 +882,15 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL: // MAV ID: 203
|
||||
case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
|
||||
// these commands takes no parameters
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
|
||||
packet.param1 = cmd.content.mount_control.pitch;
|
||||
packet.param2 = cmd.content.mount_control.roll;
|
||||
packet.param3 = cmd.content.mount_control.yaw;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
|
||||
packet.param1 = cmd.content.cam_trigg_dist.meters; // distance between camera shots in meters
|
||||
break;
|
||||
|
@ -106,6 +106,13 @@ public:
|
||||
float cycle_time; // cycle time in seconds (the time between peaks or the time the servo is at the specified pwm value for each cycle?)
|
||||
};
|
||||
|
||||
// mount control command structure
|
||||
struct PACKED Mount_Control {
|
||||
float pitch; // pitch angle in degrees
|
||||
float roll; // roll angle in degrees
|
||||
float yaw; // yaw angle (relative to vehicle heading) in degrees
|
||||
};
|
||||
|
||||
// set cam trigger distance command structure
|
||||
struct PACKED Cam_Trigg_Distance {
|
||||
float meters; // distance
|
||||
@ -153,6 +160,9 @@ public:
|
||||
// do-repeate-servo
|
||||
Repeat_Servo_Command repeat_servo;
|
||||
|
||||
// mount control
|
||||
Mount_Control mount_control;
|
||||
|
||||
// cam trigg distance
|
||||
Cam_Trigg_Distance cam_trigg_dist;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user