mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: remove get_angle_targets_for_reporting fn
this saves a tiny amount of time by removing the memory copy of a Vector3f
This commit is contained in:
parent
06e06438b3
commit
d242fcaae5
@ -276,8 +276,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
|
||||
|
||||
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||
{
|
||||
Vector3f targets;
|
||||
get_angle_targets_for_reporting(targets);
|
||||
const Vector3f &targets = attitude_control.angle_ef_targets();
|
||||
mavlink_msg_nav_controller_output_send(
|
||||
chan,
|
||||
targets.x / 1.0e2f,
|
||||
|
@ -469,8 +469,7 @@ struct PACKED log_Attitude {
|
||||
// Write an attitude packet
|
||||
static void Log_Write_Attitude()
|
||||
{
|
||||
Vector3f targets;
|
||||
get_angle_targets_for_reporting(targets);
|
||||
const Vector3f &targets = attitude_control.angle_ef_targets();
|
||||
struct log_Attitude pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
|
@ -327,8 +327,3 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
||||
}
|
||||
}
|
||||
|
||||
// get_angle_targets_for_reporting() - returns 3d vector of roll, pitch and yaw target angles for logging and reporting to GCS
|
||||
static void get_angle_targets_for_reporting(Vector3f& targets)
|
||||
{
|
||||
targets = attitude_control.angle_ef_targets();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user