Copter: bug fix to ROI to pull target from conditional command queue
This commit is contained in:
parent
f1969d5662
commit
47ab02d686
@ -1379,6 +1379,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_ROI:
|
||||
case MAV_CMD_DO_SET_ROI:
|
||||
param1 = tell_command.p1; // MAV_ROI (aka roi mode) is held in wp's parameter but we actually do nothing with it because we only support pointing at a specific location provided by x,y and z parameters
|
||||
break;
|
||||
|
||||
@ -1675,6 +1676,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_ROI:
|
||||
case MAV_CMD_DO_SET_ROI:
|
||||
tell_command.p1 = packet.param1; // MAV_ROI (aka roi mode) is held in wp's parameter but we actually do nothing with it because we only support pointing at a specific location provided by x,y and z parameters
|
||||
break;
|
||||
|
||||
|
@ -1005,12 +1005,12 @@ static void do_roi()
|
||||
#if MOUNT == ENABLED
|
||||
// check if mount type requires us to rotate the quad
|
||||
if( camera_mount.get_mount_type() != AP_Mount::k_pan_tilt && camera_mount.get_mount_type() != AP_Mount::k_pan_tilt_roll ) {
|
||||
yaw_look_at_WP = pv_location_to_vector(command_nav_queue);
|
||||
yaw_look_at_WP = pv_location_to_vector(command_cond_queue);
|
||||
set_yaw_mode(YAW_LOOK_AT_LOCATION);
|
||||
}
|
||||
// send the command to the camera mount
|
||||
camera_mount.set_roi_cmd(&command_nav_queue);
|
||||
|
||||
camera_mount.set_roi_cmd(&command_cond_queue);
|
||||
|
||||
// TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below)
|
||||
// 0: do nothing
|
||||
// 1: point at next waypoint
|
||||
@ -1019,7 +1019,7 @@ static void do_roi()
|
||||
// 4: point at a target given a target id (can't be implemented)
|
||||
#else
|
||||
// if we have no camera mount aim the quad at the location
|
||||
yaw_look_at_WP = pv_location_to_vector(command_nav_queue);
|
||||
yaw_look_at_WP = pv_location_to_vector(command_cond_queue);
|
||||
set_yaw_mode(YAW_LOOK_AT_LOCATION);
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user