Mount: remove support for do-mount-configure as command long

Also fix bug in do-mount-control so that do-mount-control can switch mount into retract mode

Also removes ability to set which axis are stabilized through
ardupilotmega mount_configure message
This commit is contained in:
Randy Mackay 2015-09-05 15:42:42 +09:00
parent 8320c06700
commit fa0aa6f5c9
4 changed files with 5 additions and 33 deletions

View File

@ -625,16 +625,6 @@ void AP_Mount::configure_msg(uint8_t instance, mavlink_message_t* msg)
_backends[instance]->configure_msg(msg);
}
void AP_Mount::configure(uint8_t instance, enum MAV_MOUNT_MODE mount_mode, uint8_t stab_roll, uint8_t stab_tilt, uint8_t stab_pan)
{
if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == NULL) {
return;
}
// send message to backend
_backends[instance]->configure(mount_mode, stab_roll, stab_tilt, stab_pan);
}
/// Control the mount (depends on the previously set mount configuration)
/// triggered by a MavLink packet.
void AP_Mount::control_msg(uint8_t instance, mavlink_message_t *msg)

View File

@ -114,10 +114,6 @@ public:
void set_roi_target(const struct Location &target_loc) { set_roi_target(_primary,target_loc); }
void set_roi_target(uint8_t instance, const struct Location &target_loc);
// configure - configure the mount
void configure(enum MAV_MOUNT_MODE mount_mode, uint8_t stab_roll, uint8_t stab_tilt, uint8_t stab_pan) { configure(_primary, mount_mode, stab_roll, stab_tilt, stab_pan); }
void configure(uint8_t instance, enum MAV_MOUNT_MODE mount_mode, uint8_t stab_roll, uint8_t stab_tilt, uint8_t stab_pan);
// control - control the mount
void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, enum MAV_MOUNT_MODE mount_mode) { control(_primary, pitch_or_lat, roll_or_lon, yaw_or_alt, mount_mode); }
void control(uint8_t instance, int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, enum MAV_MOUNT_MODE mount_mode);

View File

@ -32,17 +32,7 @@ void AP_Mount_Backend::configure_msg(mavlink_message_t* msg)
__mavlink_mount_configure_t packet;
mavlink_msg_mount_configure_decode(msg, &packet);
configure((MAV_MOUNT_MODE)packet.mount_mode, packet.stab_roll, packet.stab_pitch, packet.stab_yaw);
}
void AP_Mount_Backend::configure(MAV_MOUNT_MODE mount_mode, uint8_t stab_roll, uint8_t stab_tilt, uint8_t stab_pan)
{
// set mode
_frontend.set_mode(_instance, mount_mode);
// set which axis are stabilized
_state._stab_roll = stab_roll;
_state._stab_tilt = stab_tilt;
_state._stab_pan = stab_pan;
set_mode((MAV_MOUNT_MODE)packet.mount_mode);
}
// control_msg - process MOUNT_CONTROL messages received from GCS. deprecated.
@ -51,14 +41,12 @@ void AP_Mount_Backend::control_msg(mavlink_message_t *msg)
__mavlink_mount_control_t packet;
mavlink_msg_mount_control_decode(msg, &packet);
control((int32_t) packet.input_a, (int32_t) packet.input_b, (int32_t) packet.input_c, 0);
control((int32_t)packet.input_a, (int32_t)packet.input_b, (int32_t)packet.input_c, _state._mode);
}
void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, uint8_t mount_mode)
void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode)
{
if(mount_mode > 0) {
_frontend.set_mode(_instance, (MAV_MOUNT_MODE) mount_mode);
}
_frontend.set_mode(_instance, mount_mode);
// interpret message fields based on mode
switch (_frontend.get_mode(_instance)) {

View File

@ -56,10 +56,8 @@ public:
// set_roi_target - sets target location that mount should attempt to point towards
virtual void set_roi_target(const struct Location &target_loc);
// configure - configure the mount
virtual void configure(MAV_MOUNT_MODE mount_mode, uint8_t stab_roll, uint8_t stab_tilt, uint8_t stab_pan);
// control - control the mount
virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, uint8_t mount_mode);
virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode);
// configure_msg - process MOUNT_CONFIGURE messages received from GCS
virtual void configure_msg(mavlink_message_t* msg);