2016-12-23 02:03:21 -04:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2023-04-05 09:25:54 -03:00
# include "AP_Proximity_config.h"
# if AP_PROXIMITY_MAV_ENABLED
2021-03-25 04:32:09 -03:00
2023-04-05 09:25:54 -03:00
# include "AP_Proximity_MAV.h"
2021-03-25 04:32:09 -03:00
# include <AP_HAL/AP_HAL.h>
2016-12-23 02:03:21 -04:00
# include <ctype.h>
# include <stdio.h>
extern const AP_HAL : : HAL & hal ;
2018-10-23 23:42:09 -03:00
# define PROXIMITY_MAV_TIMEOUT_MS 500 // distance messages must arrive within this many milliseconds
2021-04-18 16:33:21 -03:00
# define PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS 50 // obstacles will be transferred from temp boundary to actual boundary if mavlink message does not arrive within this many milliseconds
2020-12-14 03:59:11 -04:00
2016-12-23 02:03:21 -04:00
// update the state of the sensor
void AP_Proximity_MAV : : update ( void )
{
// check for timeout and set health status
2017-04-12 05:59:40 -03:00
if ( ( _last_update_ms = = 0 | | ( AP_HAL : : millis ( ) - _last_update_ms > PROXIMITY_MAV_TIMEOUT_MS ) ) & &
( _last_upward_update_ms = = 0 | | ( AP_HAL : : millis ( ) - _last_upward_update_ms > PROXIMITY_MAV_TIMEOUT_MS ) ) ) {
2019-09-27 05:58:52 -03:00
set_status ( AP_Proximity : : Status : : NoData ) ;
2016-12-23 02:03:21 -04:00
} else {
2019-09-27 05:58:52 -03:00
set_status ( AP_Proximity : : Status : : Good ) ;
2016-12-23 02:03:21 -04:00
}
}
2017-01-16 02:58:14 -04:00
// get distance upwards in meters. returns true on success
bool AP_Proximity_MAV : : get_upward_distance ( float & distance ) const
{
if ( ( _last_upward_update_ms ! = 0 ) & & ( AP_HAL : : millis ( ) - _last_upward_update_ms < = PROXIMITY_MAV_TIMEOUT_MS ) ) {
distance = _distance_upward ;
return true ;
}
return false ;
}
2021-01-10 14:14:24 -04:00
// handle mavlink messages
2019-04-30 07:22:49 -03:00
void AP_Proximity_MAV : : handle_msg ( const mavlink_message_t & msg )
2021-01-10 14:14:24 -04:00
{
switch ( msg . msgid ) {
case ( MAVLINK_MSG_ID_DISTANCE_SENSOR ) :
handle_distance_sensor_msg ( msg ) ;
break ;
case ( MAVLINK_MSG_ID_OBSTACLE_DISTANCE ) :
handle_obstacle_distance_msg ( msg ) ;
break ;
case ( MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D ) :
handle_obstacle_distance_3d_msg ( msg ) ;
break ;
}
}
// handle mavlink DISTANCE_SENSOR messages
void AP_Proximity_MAV : : handle_distance_sensor_msg ( const mavlink_message_t & msg )
2016-12-23 02:03:21 -04:00
{
2021-01-10 14:14:24 -04:00
mavlink_distance_sensor_t packet ;
mavlink_msg_distance_sensor_decode ( & msg , & packet ) ;
// store distance to appropriate sector based on orientation field
if ( packet . orientation < = MAV_SENSOR_ROTATION_YAW_315 ) {
2021-03-08 13:21:45 -04:00
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 ) ) {
// push data from temp boundary to the main 3-D proximity boundary
2022-07-07 04:55:05 -03:00
temp_boundary . update_3D_boundary ( state . instance , frontend . boundary ) ;
2021-03-08 13:21:45 -04:00
// clear temp boundary for new data
temp_boundary . reset ( ) ;
}
// store in meters
const float distance = packet . current_distance * 0.01f ;
2021-01-10 14:14:24 -04:00
const uint8_t sector = packet . orientation ;
// get the face for this sector
const float yaw_angle_deg = sector * 45 ;
2022-07-07 00:35:43 -03:00
const AP_Proximity_Boundary_3D : : Face face = frontend . boundary . get_face ( yaw_angle_deg ) ;
2021-01-10 14:14:24 -04:00
_distance_min = packet . min_distance * 0.01f ;
_distance_max = packet . max_distance * 0.01f ;
2021-02-19 14:55:28 -04:00
const bool in_range = distance < = _distance_max & & distance > = _distance_min ;
2021-12-29 07:16:34 -04:00
if ( in_range & & ! ignore_reading ( yaw_angle_deg , distance , false ) ) {
2021-03-08 13:21:45 -04:00
temp_boundary . add_distance ( face , yaw_angle_deg , distance ) ;
2021-01-10 14:14:24 -04:00
// update OA database
database_push ( yaw_angle_deg , distance ) ;
2018-09-06 07:17:25 -03:00
}
2021-01-10 14:14:24 -04:00
}
2018-09-06 07:17:25 -03:00
2021-01-10 14:14:24 -04:00
// store upward distance
if ( packet . orientation = = MAV_SENSOR_ROTATION_PITCH_90 ) {
_distance_upward = packet . current_distance * 0.01f ;
_last_upward_update_ms = AP_HAL : : millis ( ) ;
}
return ;
}
// handle mavlink OBSTACLE_DISTANCE messages
void AP_Proximity_MAV : : handle_obstacle_distance_msg ( const mavlink_message_t & msg )
{
mavlink_obstacle_distance_t packet ;
mavlink_msg_obstacle_distance_decode ( & msg , & packet ) ;
// check increment (message's sector width)
float increment ;
if ( ! is_zero ( packet . increment_f ) ) {
// use increment float
increment = packet . increment_f ;
} else if ( packet . increment ! = 0 ) {
// use increment uint8_t
increment = packet . increment ;
} else {
// invalid increment
2018-09-06 07:17:25 -03:00
return ;
}
2021-01-10 14:14:24 -04:00
const uint8_t total_distances = MIN ( ( ( 360.0f / fabsf ( increment ) ) + 0.5f ) , MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN ) ; // usually 72
2018-09-06 07:17:25 -03:00
2021-01-10 14:14:24 -04:00
// set distance min and max
_distance_min = packet . min_distance * 0.01f ;
_distance_max = packet . max_distance * 0.01f ;
_last_update_ms = AP_HAL : : millis ( ) ;
2018-09-06 07:17:25 -03:00
2021-01-10 14:14:24 -04:00
// get user configured yaw correction from front end
2022-07-18 05:51:43 -03:00
const float param_yaw_offset = constrain_float ( params . yaw_correction , - 360.0f , + 360.0f ) ;
2021-01-10 14:14:24 -04:00
const float yaw_correction = wrap_360 ( param_yaw_offset + packet . angle_offset ) ;
2022-07-18 05:51:43 -03:00
if ( params . orientation ! = 0 ) {
2021-01-10 14:14:24 -04:00
increment * = - 1 ;
}
2017-01-16 02:58:14 -04:00
2021-01-10 14:14:24 -04:00
Vector3f current_pos ;
Matrix3f body_to_ned ;
const bool database_ready = database_prepare_for_push ( current_pos , body_to_ned ) ;
// variables to calculate closest angle and distance for each face
AP_Proximity_Boundary_3D : : Face face ;
2021-02-19 14:55:28 -04:00
float face_distance = FLT_MAX ;
float face_yaw_deg = 0.0f ;
2021-01-10 14:14:24 -04:00
bool face_distance_valid = false ;
2021-02-19 14:55:28 -04:00
// reset this boundary to fill with new data
2022-07-07 00:35:43 -03:00
frontend . boundary . reset ( ) ;
2021-02-19 14:55:28 -04:00
2021-01-10 14:14:24 -04:00
// iterate over message's sectors
for ( uint8_t j = 0 ; j < total_distances ; j + + ) {
const uint16_t distance_cm = packet . distances [ j ] ;
2021-02-19 14:55:28 -04:00
const float packet_distance_m = distance_cm * 0.01f ;
const float mid_angle = wrap_360 ( ( float ) j * increment + yaw_correction ) ;
const bool range_check = distance_cm = = 0 | | distance_cm = = 65535 | | distance_cm < packet . min_distance | |
distance_cm > packet . max_distance ;
2021-12-29 07:16:34 -04:00
if ( range_check | | ignore_reading ( mid_angle , packet_distance_m , false ) ) {
2021-01-10 14:14:24 -04:00
// sanity check failed, ignore this distance value
continue ;
2018-09-06 07:17:25 -03:00
}
2021-01-10 14:14:24 -04:00
// get face for this latest reading
2022-07-07 00:35:43 -03:00
AP_Proximity_Boundary_3D : : Face latest_face = frontend . boundary . get_face ( mid_angle ) ;
2021-01-10 14:14:24 -04:00
if ( latest_face ! = face ) {
// store previous face
if ( face_distance_valid ) {
2022-07-07 04:55:05 -03:00
frontend . boundary . set_face_attributes ( face , face_yaw_deg , face_distance , state . instance ) ;
2021-01-10 14:14:24 -04:00
} else {
2022-07-07 04:55:05 -03:00
frontend . boundary . reset_face ( face , state . instance ) ;
2018-09-06 07:17:25 -03:00
}
2021-01-10 14:14:24 -04:00
// init for latest face
face = latest_face ;
face_distance_valid = false ;
}
2019-06-29 02:57:09 -03:00
2021-01-10 14:14:24 -04:00
// update minimum distance found so far
if ( ! face_distance_valid | | ( packet_distance_m < face_distance ) ) {
face_yaw_deg = mid_angle ;
face_distance = packet_distance_m ;
face_distance_valid = true ;
2018-09-06 07:17:25 -03:00
}
2021-01-10 14:14:24 -04:00
// update Object Avoidance database with Earth-frame point
if ( database_ready ) {
database_push ( mid_angle , packet_distance_m , _last_update_ms , current_pos , body_to_ned ) ;
2018-09-06 07:17:25 -03:00
}
2017-01-16 02:58:14 -04:00
}
2020-12-06 08:24:40 -04:00
2021-01-10 14:14:24 -04:00
// process the last face
if ( face_distance_valid ) {
2022-07-07 04:55:05 -03:00
frontend . boundary . set_face_attributes ( face , face_yaw_deg , face_distance , state . instance ) ;
2021-01-10 14:14:24 -04:00
} else {
2022-07-07 04:55:05 -03:00
frontend . boundary . reset_face ( face , state . instance ) ;
2021-01-10 14:14:24 -04:00
}
return ;
}
2020-12-06 08:24:40 -04:00
2021-01-10 14:14:24 -04:00
// handle mavlink OBSTACLE_DISTANCE_3D messages
void AP_Proximity_MAV : : handle_obstacle_distance_3d_msg ( const mavlink_message_t & msg )
{
mavlink_obstacle_distance_3d_t packet ;
mavlink_msg_obstacle_distance_3d_decode ( & msg , & packet ) ;
2020-12-06 08:24:40 -04:00
2021-01-10 14:14:24 -04:00
const uint32_t previous_sys_time = _last_update_ms ;
_last_update_ms = AP_HAL : : millis ( ) ;
2021-03-08 13:21:45 -04:00
2021-01-10 14:14:24 -04:00
// 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 ;
2020-12-14 03:59:11 -04:00
2021-03-08 13:21:45 -04:00
const uint32_t previous_msg_timestamp = _last_msg_update_timestamp_ms ;
_last_msg_update_timestamp_ms = packet . time_boot_ms ;
2020-12-06 08:24:40 -04:00
2021-01-10 14:14:24 -04:00
if ( packet . frame ! = MAV_FRAME_BODY_FRD ) {
2021-03-08 13:21:45 -04:00
// we do not support this frame of reference yet
2021-01-10 14:14:24 -04:00
return ;
}
2020-12-14 03:59:11 -04:00
2021-03-08 13:21:45 -04:00
if ( ( previous_msg_timestamp ! = _last_msg_update_timestamp_ms ) | | ( time_diff > PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS ) ) {
2021-04-18 16:33:21 -03:00
// push data from temp boundary to the main 3-D proximity boundary because a new timestamp has arrived
2022-07-07 04:55:05 -03:00
temp_boundary . update_3D_boundary ( state . instance , frontend . boundary ) ;
2021-03-08 13:21:45 -04:00
// clear temp boundary for new data
temp_boundary . reset ( ) ;
2021-01-10 14:14:24 -04:00
}
2020-12-06 08:24:40 -04:00
2021-01-10 14:14:24 -04:00
_distance_min = packet . min_distance ;
_distance_max = packet . max_distance ;
2020-12-06 08:24:40 -04:00
2021-01-10 14:14:24 -04:00
Vector3f current_pos ;
Matrix3f body_to_ned ;
const bool database_ready = database_prepare_for_push ( current_pos , body_to_ned ) ;
2020-12-06 08:24:40 -04:00
2021-02-19 14:55:28 -04:00
const Vector3f obstacle_FRD ( packet . x , packet . y , packet . z ) ;
const float obstacle_distance = obstacle_FRD . length ( ) ;
if ( obstacle_distance < _distance_min | | obstacle_distance > _distance_max | | is_zero ( obstacle_distance ) ) {
2021-01-10 14:14:24 -04:00
// message isn't healthy
return ;
}
2021-02-19 14:55:28 -04:00
// convert to FRU
const Vector3f obstacle ( obstacle_FRD . x , obstacle_FRD . y , obstacle_FRD . z * - 1.0f ) ;
2021-01-10 14:14:24 -04:00
// extract yaw and pitch from Obstacle Vector
const float yaw = wrap_360 ( degrees ( atan2f ( obstacle . y , obstacle . x ) ) ) ;
2021-09-11 07:35:38 -03:00
const float pitch = wrap_180 ( degrees ( M_PI_2 - atan2f ( obstacle . xy ( ) . length ( ) , obstacle . z ) ) ) ;
2021-01-10 14:14:24 -04:00
2021-12-29 07:16:34 -04:00
if ( ignore_reading ( pitch , yaw , obstacle_distance , false ) ) {
// obstacle is probably near ground or out of range
return ;
}
2021-01-10 14:14:24 -04:00
// allot to correct layer and sector based on calculated pitch and yaw
2022-07-07 00:35:43 -03:00
const AP_Proximity_Boundary_3D : : Face face = frontend . boundary . get_face ( pitch , yaw ) ;
2021-03-08 13:21:45 -04:00
temp_boundary . add_distance ( face , pitch , yaw , obstacle . length ( ) ) ;
2021-01-10 14:14:24 -04:00
if ( database_ready ) {
database_push ( yaw , pitch , obstacle . length ( ) , _last_update_ms , current_pos , body_to_ned ) ;
2020-12-06 08:24:40 -04:00
}
2021-01-10 14:14:24 -04:00
return ;
2016-12-23 02:03:21 -04:00
}
2021-03-25 04:32:09 -03:00
2023-04-05 09:25:54 -03:00
# endif // AP_PROXIMITY_MAV_ENABLED