mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Mount: gimbal_manager_set_pitchyaw is not a command
This commit is contained in:
parent
c1831bae32
commit
4ffdb65288
@ -380,7 +380,7 @@ MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_configure(const mavlink_co
|
|||||||
return backend->handle_command_do_gimbal_manager_configure(packet, msg);
|
return backend->handle_command_do_gimbal_manager_configure(packet, msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){
|
void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg) {
|
||||||
mavlink_gimbal_manager_set_attitude_t packet;
|
mavlink_gimbal_manager_set_attitude_t packet;
|
||||||
mavlink_msg_gimbal_manager_set_attitude_decode(&msg,&packet);
|
mavlink_msg_gimbal_manager_set_attitude_decode(&msg,&packet);
|
||||||
|
|
||||||
@ -445,7 +445,7 @@ void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Mount::handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg)
|
void AP_Mount::handle_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
mavlink_gimbal_manager_set_pitchyaw_t packet;
|
mavlink_gimbal_manager_set_pitchyaw_t packet;
|
||||||
mavlink_msg_gimbal_manager_set_pitchyaw_decode(&msg,&packet);
|
mavlink_msg_gimbal_manager_set_pitchyaw_decode(&msg,&packet);
|
||||||
@ -906,7 +906,7 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m
|
|||||||
handle_gimbal_manager_set_attitude(msg);
|
handle_gimbal_manager_set_attitude(msg);
|
||||||
break;
|
break;
|
||||||
case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW:
|
case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW:
|
||||||
handle_command_gimbal_manager_set_pitchyaw(msg);
|
handle_gimbal_manager_set_pitchyaw(msg);
|
||||||
break;
|
break;
|
||||||
case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION:
|
case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION:
|
||||||
handle_gimbal_device_information(msg);
|
handle_gimbal_device_information(msg);
|
||||||
|
@ -296,7 +296,7 @@ private:
|
|||||||
MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||||
void handle_gimbal_manager_set_attitude(const mavlink_message_t &msg);
|
void handle_gimbal_manager_set_attitude(const mavlink_message_t &msg);
|
||||||
void handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg);
|
void handle_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg);
|
||||||
void handle_global_position_int(const mavlink_message_t &msg);
|
void handle_global_position_int(const mavlink_message_t &msg);
|
||||||
void handle_gimbal_device_information(const mavlink_message_t &msg);
|
void handle_gimbal_device_information(const mavlink_message_t &msg);
|
||||||
void handle_gimbal_device_attitude_status(const mavlink_message_t &msg);
|
void handle_gimbal_device_attitude_status(const mavlink_message_t &msg);
|
||||||
|
@ -259,7 +259,7 @@ void AP_Mount_Alexmos::read_incoming()
|
|||||||
|
|
||||||
numc = _port->available();
|
numc = _port->available();
|
||||||
|
|
||||||
if (numc < 0 ){
|
if (numc < 0 ) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -106,7 +106,7 @@ void AP_Mount_Backend::clear_roi_target()
|
|||||||
_roi_target_set = false;
|
_roi_target_set = false;
|
||||||
|
|
||||||
// reset the mode if in GPS tracking mode
|
// reset the mode if in GPS tracking mode
|
||||||
if (_mode == MAV_MOUNT_MODE_GPS_POINT) {
|
if (get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
|
||||||
MAV_MOUNT_MODE default_mode = (MAV_MOUNT_MODE)_params.default_mode.get();
|
MAV_MOUNT_MODE default_mode = (MAV_MOUNT_MODE)_params.default_mode.get();
|
||||||
set_mode(default_mode);
|
set_mode(default_mode);
|
||||||
}
|
}
|
||||||
|
@ -219,7 +219,7 @@ void AP_Mount_SToRM32_serial::read_incoming() {
|
|||||||
|
|
||||||
numc = _port->available();
|
numc = _port->available();
|
||||||
|
|
||||||
if (numc < 0 ){
|
if (numc < 0 ) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user