mirror of https://github.com/ArduPilot/ardupilot
Rover: integrate mount frontend-backend restructure
rename mount.set_roi_cmd to set_roi_target
This commit is contained in:
parent
c51ba8cd03
commit
1ab405bf88
|
@ -286,7 +286,7 @@ static struct Location current_loc;
|
||||||
// --------------------------------------
|
// --------------------------------------
|
||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
// current_loc uses the baro/gps soloution for altitude rather than gps only.
|
// current_loc uses the baro/gps soloution for altitude rather than gps only.
|
||||||
AP_Mount camera_mount(¤t_loc, ahrs, 0);
|
AP_Mount camera_mount(ahrs, current_loc);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
@ -616,7 +616,7 @@ static void ahrs_update()
|
||||||
static void mount_update(void)
|
static void mount_update(void)
|
||||||
{
|
{
|
||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
camera_mount.update_mount_position();
|
camera_mount.update();
|
||||||
#endif
|
#endif
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
camera.trigger_pic_cleanup();
|
camera.trigger_pic_cleanup();
|
||||||
|
@ -705,10 +705,6 @@ static void update_logging2(void)
|
||||||
static void update_aux(void)
|
static void update_aux(void)
|
||||||
{
|
{
|
||||||
RC_Channel_aux::enable_aux_servos();
|
RC_Channel_aux::enable_aux_servos();
|
||||||
|
|
||||||
#if MOUNT == ENABLED
|
|
||||||
camera_mount.update_mount_type();
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -729,10 +725,6 @@ static void one_second_loop(void)
|
||||||
// cope with changes to aux functions
|
// cope with changes to aux functions
|
||||||
update_aux();
|
update_aux();
|
||||||
|
|
||||||
#if MOUNT == ENABLED
|
|
||||||
camera_mount.update_mount_type();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// cope with changes to mavlink system ID
|
// cope with changes to mavlink system ID
|
||||||
mavlink_system.sysid = g.sysid_this_mav;
|
mavlink_system.sysid = g.sysid_this_mav;
|
||||||
|
|
||||||
|
|
|
@ -830,7 +830,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// send the command to the camera mount
|
// send the command to the camera mount
|
||||||
camera_mount.set_roi_cmd(&roi_loc);
|
camera_mount.set_roi_target(roi_loc);
|
||||||
}
|
}
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -162,7 +162,7 @@ public:
|
||||||
//
|
//
|
||||||
k_param_camera,
|
k_param_camera,
|
||||||
k_param_camera_mount,
|
k_param_camera_mount,
|
||||||
k_param_camera_mount2,
|
k_param_camera_mount2, // unused
|
||||||
|
|
||||||
//
|
//
|
||||||
// 240: PID Controllers
|
// 240: PID Controllers
|
||||||
|
|
|
@ -104,17 +104,9 @@ start_command(const AP_Mission::Mission_Command& cmd)
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// send the command to the camera mount
|
// send the command to the camera mount
|
||||||
camera_mount.set_roi_cmd(&cmd.content.location);
|
camera_mount.set_roi_target(cmd.content.location);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_MOUNT_CONFIGURE: // Mission command to configure a camera mount |Mount operation mode (see MAV_CONFIGURE_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
|
|
||||||
camera_mount.configure_cmd();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_DO_MOUNT_CONTROL: // Mission command to control a camera mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|
|
|
||||||
camera_mount.control_cmd();
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
|
|
@ -196,6 +196,9 @@ static void init_ardupilot()
|
||||||
|
|
||||||
relay.init();
|
relay.init();
|
||||||
|
|
||||||
|
// initialise camera mount
|
||||||
|
camera_mount.init();
|
||||||
|
|
||||||
/*
|
/*
|
||||||
setup the 'main loop is dead' check. Note that this relies on
|
setup the 'main loop is dead' check. Note that this relies on
|
||||||
the RC library being initialised.
|
the RC library being initialised.
|
||||||
|
|
Loading…
Reference in New Issue