AP_Proximity: remove unnecessary const from database_push

also shorten current_vehicle_bearing argument to just current_heading
This commit is contained in:
Randy Mackay 2019-11-27 10:32:56 +09:00
parent 1ba5f4626d
commit f60ec91993
4 changed files with 18 additions and 18 deletions

View File

@ -335,7 +335,7 @@ bool AP_Proximity_Backend::get_next_ignore_start_or_end(uint8_t start_or_end, in
}
// returns true if database is ready to be pushed to and all cached data is ready
bool AP_Proximity_Backend::database_prepare_for_push(Location &current_loc, float &current_vehicle_bearing)
bool AP_Proximity_Backend::database_prepare_for_push(Location &current_loc, float &current_heading)
{
AP_OADatabase *oaDb = AP::oadatabase();
if (oaDb == nullptr || !oaDb->healthy()) {
@ -346,22 +346,22 @@ bool AP_Proximity_Backend::database_prepare_for_push(Location &current_loc, floa
return false;
}
current_vehicle_bearing = AP::ahrs().yaw_sensor * 0.01f;
current_heading = AP::ahrs().yaw_sensor * 0.01f;
return true;
}
// update Object Avoidance database with Earth-frame point
void AP_Proximity_Backend::database_push(const float angle, const float distance)
void AP_Proximity_Backend::database_push(float angle, float distance)
{
Location current_loc;
float current_vehicle_bearing;
if (database_prepare_for_push(current_loc, current_vehicle_bearing) == true) {
database_push(angle, distance, AP_HAL::millis(), current_loc, current_vehicle_bearing);
float current_heading;
if (database_prepare_for_push(current_loc, current_heading)) {
database_push(angle, distance, AP_HAL::millis(), current_loc, current_heading);
}
}
// update Object Avoidance database with Earth-frame point
void AP_Proximity_Backend::database_push(const float angle, const float distance, const uint32_t timestamp_ms, const Location &current_loc, const float current_vehicle_bearing)
void AP_Proximity_Backend::database_push(float angle, float distance, uint32_t timestamp_ms, const Location &current_loc, float current_heading)
{
AP_OADatabase *oaDb = AP::oadatabase();
if (oaDb == nullptr || !oaDb->healthy()) {
@ -369,6 +369,6 @@ void AP_Proximity_Backend::database_push(const float angle, const float distance
}
Location temp_loc = current_loc;
temp_loc.offset_bearing(wrap_180(current_vehicle_bearing + angle), distance);
temp_loc.offset_bearing(wrap_180(current_heading + angle), distance);
oaDb->queue_push(temp_loc, timestamp_ms, distance, angle);
}

View File

@ -87,10 +87,10 @@ protected:
bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const;
bool get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const;
// database helpers
bool database_prepare_for_push(Location &current_loc, float &current_vehicle_bearing);
void database_push(const float angle, const float distance);
void database_push(const float angle, const float distance, const uint32_t timestamp_ms, const Location &current_loc, const float current_vehicle_bearing);
// database helpers. all angles are in degrees
bool database_prepare_for_push(Location &current_loc, float &current_heading);
void database_push(float angle, float distance);
void database_push(float angle, float distance, uint32_t timestamp_ms, const Location &current_loc, float current_heading);
AP_Proximity &frontend;
AP_Proximity::Proximity_State &state; // reference to this instances state

View File

@ -391,8 +391,8 @@ void AP_Proximity_LightWareSF40C::process_message()
// prepare to push to object database
Location current_loc;
float current_vehicle_bearing;
const bool database_ready = database_prepare_for_push(current_loc, current_vehicle_bearing);
float current_heading;
const bool database_ready = database_prepare_for_push(current_loc, current_heading);
// process each point
const float angle_inc_deg = (1.0f / point_total) * 360.0f;
@ -426,7 +426,7 @@ void AP_Proximity_LightWareSF40C::process_message()
}
// send point to object avoidance database
if (database_ready) {
database_push(angle_deg, dist_m, _last_distance_received_ms, current_loc, current_vehicle_bearing);
database_push(angle_deg, dist_m, _last_distance_received_ms, current_loc, current_heading);
}
}
}

View File

@ -104,8 +104,8 @@ void AP_Proximity_MAV::handle_msg(const mavlink_message_t &msg)
}
Location current_loc;
float current_vehicle_bearing;
const bool database_ready = database_prepare_for_push(current_loc, current_vehicle_bearing);
float current_heading;
const bool database_ready = database_prepare_for_push(current_loc, current_heading);
// initialise updated array and proximity sector angles (to closest object) and distances
bool sector_updated[_num_sectors];
@ -145,7 +145,7 @@ void AP_Proximity_MAV::handle_msg(const mavlink_message_t &msg)
// update Object Avoidance database with Earth-frame point
if (database_ready) {
database_push(mid_angle, packet_distance_m, _last_update_ms, current_loc, current_vehicle_bearing);
database_push(mid_angle, packet_distance_m, _last_update_ms, current_loc, current_heading);
}
}