mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: save some bytes by removing empty methods based on #ifs
This commit is contained in:
parent
cbd591f2ba
commit
3480a8f9f9
|
@ -729,10 +729,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_MOUNT_ENABLED
|
||||||
MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
switch (packet.command) {
|
switch (packet.command) {
|
||||||
#if HAL_MOUNT_ENABLED
|
|
||||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||||
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
|
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
|
||||||
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
|
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
|
||||||
|
@ -742,12 +742,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t
|
||||||
0.0f);
|
0.0f);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
return GCS_MAVLINK::handle_command_mount(packet);
|
return GCS_MAVLINK::handle_command_mount(packet);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
|
@ -1025,10 +1025,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_comma
|
||||||
return MAV_RESULT_DENIED;
|
return MAV_RESULT_DENIED;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_MOUNT_ENABLED
|
||||||
void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
|
void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
switch (msg.msgid) {
|
switch (msg.msgid) {
|
||||||
#if HAL_MOUNT_ENABLED
|
|
||||||
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
||||||
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
|
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
|
||||||
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
|
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
|
||||||
|
@ -1039,10 +1039,10 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
GCS_MAVLINK::handle_mount_message(msg);
|
GCS_MAVLINK::handle_mount_message(msg);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
|
void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
|
|
|
@ -29,13 +29,17 @@ protected:
|
||||||
|
|
||||||
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
||||||
MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet) override;
|
MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet) override;
|
||||||
|
#if HAL_MOUNT_ENABLED
|
||||||
MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet) override;
|
MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet) override;
|
||||||
|
#endif
|
||||||
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override;
|
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override;
|
||||||
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
|
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
|
||||||
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_pause_continue(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_pause_continue(const mavlink_command_int_t &packet);
|
||||||
|
|
||||||
|
#if HAL_MOUNT_ENABLED
|
||||||
void handle_mount_message(const mavlink_message_t &msg) override;
|
void handle_mount_message(const mavlink_message_t &msg) override;
|
||||||
|
#endif
|
||||||
|
|
||||||
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
|
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue