@ -23,7 +23,7 @@
@@ -23,7 +23,7 @@
extern const AP_HAL : : HAL & hal ;
# define PROXIMITY_MAV_TIMEOUT_MS 500 // distance messages must arrive within this many milliseconds
# define PROXIMITY_3D_MSG_TIMEOUT_MS 50 // boundary will be reset if OBSTACLE_DISTANCE_3D message does not arrive within this many milliseconds
# define PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS 50 // boundary will be reset if mavlink message does not arrive within this many milliseconds
// update the state of the sensor
void AP_Proximity_MAV : : update ( void )
@ -73,24 +73,39 @@ void AP_Proximity_MAV::handle_distance_sensor_msg(const mavlink_message_t &msg)
@@ -73,24 +73,39 @@ void AP_Proximity_MAV::handle_distance_sensor_msg(const mavlink_message_t &msg)
// store distance to appropriate sector based on orientation field
if ( packet . orientation < = MAV_SENSOR_ROTATION_YAW_315 ) {
const uint32_t previous_sys_time = _last_update_ms ;
_last_update_ms = AP_HAL : : millis ( ) ;
// time_diff will check if the new message arrived significantly later than the last message
const uint32_t time_diff = _last_update_ms - previous_sys_time ;
const uint32_t previous_msg_timestamp = _last_msg_update_timestamp_ms ;
_last_msg_update_timestamp_ms = packet . time_boot_ms ;
// we will add on to the last fence if the time stamp is the same
// provided we got the new obstacle in less than PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS
if ( ( previous_msg_timestamp ! = _last_msg_update_timestamp_ms ) | | ( time_diff > PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS ) ) {
// cleared fence back to defaults since we have a new timestamp
boundary . reset ( ) ;
// push data from temp boundary to the main 3-D proximity boundary
temp_boundary . update_3D_boundary ( boundary ) ;
// clear temp boundary for new data
temp_boundary . reset ( ) ;
}
// store in meters
const float distance = packet . current_distance * 0.01f ;
const uint8_t sector = packet . orientation ;
// get the face for this sector
const float yaw_angle_deg = sector * 45 ;
const AP_Proximity_Boundary_3D : : Face face = boundary . get_face ( yaw_angle_deg ) ;
// store in meters
const float distance = packet . current_distance * 0.01f ;
_distance_min = packet . min_distance * 0.01f ;
_distance_max = packet . max_distance * 0.01f ;
const bool in_range = distance < = _distance_max & & distance > = _distance_min ;
if ( in_range & & ! check_obstacle_near_ground ( yaw_angle_deg , distance ) ) {
boundary . set_face_attributes ( face , yaw_angle_deg , distance ) ;
temp_ boundary. add_di stan ce( face , yaw_angle_deg , distance ) ;
// update OA database
database_push ( yaw_angle_deg , distance ) ;
} else {
// reset distance for this face
boundary . reset_face ( face ) ;
}
_last_update_ms = AP_HAL : : millis ( ) ;
}
// store upward distance
@ -204,23 +219,27 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t &
@@ -204,23 +219,27 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t &
const uint32_t previous_sys_time = _last_update_ms ;
_last_update_ms = AP_HAL : : millis ( ) ;
// time_diff will check if the new message arrived significantly later than the last message
const uint32_t time_diff = _last_update_ms - previous_sys_time ;
const uint32_t previous_msg_timestamp = _last_3d_ msg_update_ms ;
_last_3d_ msg_update_ms = packet . time_boot_ms ;
const uint32_t previous_msg_timestamp = _last_msg_update_timestamp _ms ;
_last_msg_update_timestamp _ms = packet . time_boot_ms ;
if ( packet . frame ! = MAV_FRAME_BODY_FRD ) {
// we do not support this frame of reference yet
// we do not support this frame of reference yet
return ;
}
// we will add on to the last fence if the time stamp is the same
// provided we got the new obstacle in less than PROXIMITY_3D_MSG_TIMEOUT_MS
if ( ( previous_msg_timestamp ! = _last_3d_ msg_update_ms ) | | ( time_diff > PROXIMITY_3D _MSG_TIMEOUT_MS ) ) {
// provided we got the new obstacle in less than PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS
if ( ( previous_msg_timestamp ! = _last_msg_update_timestamp _ms ) | | ( time_diff > PROXIMITY_TIMESTAMP _MSG_TIMEOUT_MS ) ) {
// cleared fence back to defaults since we have a new timestamp
boundary . reset ( ) ;
// push data from temp boundary to the main 3-D proximity boundary
temp_boundary . update_3D_boundary ( boundary ) ;
// clear temp boundary for new data
temp_boundary . reset ( ) ;
}
_distance_min = packet . min_distance ;
@ -250,13 +269,7 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t &
@@ -250,13 +269,7 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t &
// allot to correct layer and sector based on calculated pitch and yaw
const AP_Proximity_Boundary_3D : : Face face = boundary . get_face ( pitch , yaw ) ;
float face_distance ;
if ( boundary . get_distance ( face , face_distance ) & & ( face_distance < obstacle . length ( ) ) ) {
// we already have a shorter distance in this layer and sector
return ;
}
boundary . set_face_attributes ( face , yaw , pitch , obstacle . length ( ) ) ;
temp_boundary . add_distance ( face , pitch , yaw , obstacle . length ( ) ) ;
if ( database_ready ) {
database_push ( yaw , pitch , obstacle . length ( ) , _last_update_ms , current_pos , body_to_ned ) ;