2017-03-01 07:17:45 -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/>.
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
2020-04-06 00:17:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
|
|
|
|
|
|
|
#ifndef HAL_VISUALODOM_ENABLED
|
|
|
|
#define HAL_VISUALODOM_ENABLED !HAL_MINIMIZE_FEATURES
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if HAL_VISUALODOM_ENABLED
|
|
|
|
|
2017-03-01 07:17:45 -04:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2018-04-06 05:05:14 -03:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2017-03-01 07:17:45 -04:00
|
|
|
|
|
|
|
class AP_VisualOdom_Backend;
|
|
|
|
|
|
|
|
#define AP_VISUALODOM_TIMEOUT_MS 300
|
|
|
|
|
|
|
|
class AP_VisualOdom
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
|
|
|
AP_VisualOdom();
|
|
|
|
|
2018-04-06 05:05:14 -03:00
|
|
|
// get singleton instance
|
|
|
|
static AP_VisualOdom *get_singleton() {
|
|
|
|
return _singleton;
|
|
|
|
}
|
|
|
|
|
2017-03-01 07:17:45 -04:00
|
|
|
// external position backend types (used by _TYPE parameter)
|
|
|
|
enum AP_VisualOdom_Type {
|
2020-04-03 01:38:37 -03:00
|
|
|
AP_VisualOdom_Type_None = 0,
|
|
|
|
AP_VisualOdom_Type_MAV = 1,
|
|
|
|
AP_VisualOdom_Type_IntelT265 = 2
|
2017-03-01 07:17:45 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
// detect and initialise any sensors
|
|
|
|
void init();
|
|
|
|
|
|
|
|
// return true if sensor is enabled
|
|
|
|
bool enabled() const;
|
|
|
|
|
|
|
|
// return true if sensor is basically healthy (we are receiving data)
|
|
|
|
bool healthy() const;
|
|
|
|
|
2020-04-02 09:04:44 -03:00
|
|
|
// get user defined orientation
|
|
|
|
enum Rotation get_orientation() const { return (enum Rotation)_orientation.get(); }
|
|
|
|
|
2020-04-09 21:41:14 -03:00
|
|
|
// get user defined scaling applied to position estimates
|
|
|
|
float get_pos_scale() const { return _pos_scale; }
|
|
|
|
|
2017-03-01 07:17:45 -04:00
|
|
|
// return a 3D vector defining the position offset of the camera in meters relative to the body frame origin
|
|
|
|
const Vector3f &get_pos_offset(void) const { return _pos_offset; }
|
|
|
|
|
2020-03-31 02:41:54 -03:00
|
|
|
// consume vision_position_delta mavlink messages
|
|
|
|
void handle_vision_position_delta_msg(const mavlink_message_t &msg);
|
2017-03-01 07:17:45 -04:00
|
|
|
|
2020-03-26 01:38:51 -03:00
|
|
|
// general purpose methods to consume position estimate data and send to EKF
|
|
|
|
// distances in meters, roll, pitch and yaw are in radians
|
2020-04-10 01:36:26 -03:00
|
|
|
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, uint8_t reset_counter);
|
|
|
|
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, uint8_t reset_counter);
|
2020-03-26 01:38:51 -03:00
|
|
|
|
|
|
|
// calibrate camera attitude to align with vehicle's AHRS/EKF attitude
|
|
|
|
void align_sensor_to_vehicle();
|
|
|
|
|
|
|
|
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
|
|
|
|
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const;
|
|
|
|
|
2017-03-01 07:17:45 -04:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
2018-04-06 05:05:14 -03:00
|
|
|
static AP_VisualOdom *_singleton;
|
|
|
|
|
2017-03-01 07:17:45 -04:00
|
|
|
// parameters
|
2020-04-09 21:41:14 -03:00
|
|
|
AP_Int8 _type; // sensor type
|
2017-03-01 07:17:45 -04:00
|
|
|
AP_Vector3f _pos_offset; // position offset of the camera in the body frame
|
|
|
|
AP_Int8 _orientation; // camera orientation on vehicle frame
|
2020-04-09 21:41:14 -03:00
|
|
|
AP_Float _pos_scale; // position scale factor applied to sensor values
|
2017-03-01 07:17:45 -04:00
|
|
|
|
|
|
|
// reference to backends
|
|
|
|
AP_VisualOdom_Backend *_driver;
|
|
|
|
};
|
2018-04-06 05:05:14 -03:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_VisualOdom *visualodom();
|
|
|
|
};
|
2020-04-06 00:17:42 -03:00
|
|
|
|
|
|
|
#endif // HAL_VISUALODOM_ENABLED
|