diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 4b26c1a519..ce9eae5f90 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -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) diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 82ef4766b7..017e4ab8c3 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -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); diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index afde3cfabb..de48c467c7 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -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)) { diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index c2dc69449f..221f310fec 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -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);