Browse Source

AP_Avoidance: tidy construction of vector on stack

gps-1.3.1
Peter Barker 3 years ago committed by Peter Barker
parent
commit
e2ced65c04
  1. 8
      libraries/AP_Avoidance/AP_Avoidance.cpp

8
libraries/AP_Avoidance/AP_Avoidance.cpp

@ -599,9 +599,11 @@ void AP_Avoidance::handle_msg(const mavlink_message_t &msg) @@ -599,9 +599,11 @@ void AP_Avoidance::handle_msg(const mavlink_message_t &msg)
int32_t(packet.alt * 0.1), // mm -> cm
Location::AltFrame::ABSOLUTE
};
Vector3f vel = Vector3f(packet.vx/100.0f, // cm to m
packet.vy/100.0f,
packet.vz/100.0f);
const Vector3f vel {
packet.vx * 0.01f, // cm to m
packet.vy * 0.01f,
packet.vz * 0.01f
};
add_obstacle(AP_HAL::millis(),
MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT,
msg.sysid,

Loading…
Cancel
Save