gazebo_mavlink_interface.h
10.1 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
/*
* Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
* Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
* Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
* Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
* Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
* Copyright 2015-2018 PX4 Pro Development Team
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <vector>
#include <regex>
#include <thread>
#include <mutex>
#include <condition_variable>
#include <deque>
#include <atomic>
#include <chrono>
#include <memory>
#include <sstream>
#include <cassert>
#include <stdexcept>
#include <boost/asio.hpp>
#include <boost/bind.hpp>
#include <boost/shared_array.hpp>
#include <boost/system/system_error.hpp>
#include <iostream>
#include <random>
#include <stdio.h>
#include <math.h>
#include <cstdlib>
#include <string>
#include <sys/socket.h>
#include <netinet/in.h>
#include <Eigen/Eigen>
#include <gazebo/gazebo.hh>
#include <gazebo/common/common.hh>
#include <gazebo/common/Plugin.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/transport/transport.hh>
#include <gazebo/msgs/msgs.hh>
#include <ignition/math.hh>
#include <sdf/sdf.hh>
#include <common.h>
#include <Airspeed.pb.h>
#include <CommandMotorSpeed.pb.h>
#include <MotorSpeed.pb.h>
#include <Imu.pb.h>
#include <OpticalFlow.pb.h>
#include <Range.pb.h>
#include <SITLGps.pb.h>
#include <IRLock.pb.h>
#include <Groundtruth.pb.h>
#include <Odometry.pb.h>
#include <MagneticField.pb.h>
#include <Pressure.pb.h>
#include <Wind.pb.h>
#include "mavlink_interface.h"
#include "msgbuffer.h"
//! Default distance sensor model joint naming
static const std::regex kDefaultLidarModelNaming(".*(lidar|sf10a)(.*)");
static const std::regex kDefaultSonarModelNaming(".*(sonar|mb1240-xl-ez4)(.*)");
static const std::regex kDefaultGPSModelNaming(".*(gps|ublox-neo-7M)(.*)");
static const std::regex kDefaultAirspeedModelJointNaming(".*(airspeed)(.*_joint)");
namespace gazebo {
typedef const boost::shared_ptr<const mav_msgs::msgs::CommandMotorSpeed> CommandMotorSpeedPtr;
typedef const boost::shared_ptr<const nav_msgs::msgs::Odometry> OdomPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::Airspeed> AirspeedPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::Groundtruth> GtPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::Imu> ImuPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::IRLock> IRLockPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::OpticalFlow> OpticalFlowPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::Range> SonarPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::Range> LidarPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::SITLGps> GpsPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::MagneticField> MagnetometerPtr;
typedef const boost::shared_ptr<const sensor_msgs::msgs::Pressure> BarometerPtr;
typedef const boost::shared_ptr<const physics_msgs::msgs::Wind> WindPtr;
typedef std::pair<const int, const ignition::math::Quaterniond> SensorIdRot_P;
typedef std::map<transport::SubscriberPtr, SensorIdRot_P > Sensor_M;
// Default values
static const std::string kDefaultNamespace = "";
// This just proxies the motor commands from command/motor_speed to the single motors via internal
// ConsPtr passing, such that the original commands don't have to go n_motors-times over the wire.
static const std::string kDefaultMotorVelocityReferencePubTopic = "/gazebo/command/motor_speed";
static const std::string kDefaultImuTopic = "/imu";
static const std::string kDefaultOpticalFlowTopic = "/px4flow/link/opticalFlow";
static const std::string kDefaultIRLockTopic = "/camera/link/irlock";
static const std::string kDefaultVisionTopic = "/vision_odom";
static const std::string kDefaultMagTopic = "/mag";
static const std::string kDefaultBarometerTopic = "/baro";
static const std::string kDefaultWindTopic = "/world_wind";
static const std::string kDefaultGroundtruthTopic = "/groundtruth";
//! OR operation for the enumeration and unsigned types that returns the bitmask
template<typename A, typename B>
static inline uint32_t operator |(A lhs, B rhs) {
// make it type safe
static_assert((std::is_same<A, uint32_t>::value || std::is_same<A, SensorSource>::value),
"first argument is not uint32_t or SensorSource enum type");
static_assert((std::is_same<B, uint32_t>::value || std::is_same<B, SensorSource>::value),
"second argument is not uint32_t or SensorSource enum type");
return static_cast<uint32_t> (
static_cast<std::underlying_type<SensorSource>::type>(lhs) |
static_cast<std::underlying_type<SensorSource>::type>(rhs)
);
}
class GazeboMavlinkInterface : public ModelPlugin {
public:
GazeboMavlinkInterface();
~GazeboMavlinkInterface();
void Publish();
protected:
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
void OnUpdate(const common::UpdateInfo& /*_info*/);
private:
bool received_first_actuator_{false};
Eigen::VectorXd input_reference_;
float protocol_version_{2.0};
std::unique_ptr<MavlinkInterface> mavlink_interface_;
std::string namespace_{kDefaultNamespace};
std::string motor_velocity_reference_pub_topic_{kDefaultMotorVelocityReferencePubTopic};
std::string mavlink_control_sub_topic_;
std::string link_name_;
transport::NodePtr node_handle_;
transport::PublisherPtr motor_velocity_reference_pub_;
transport::SubscriberPtr mav_control_sub_;
physics::ModelPtr model_{};
physics::WorldPtr world_{nullptr};
bool send_vision_estimation_{false};
bool send_odometry_{false};
std::vector<physics::JointPtr> joints_;
std::vector<common::PID> pids_;
std::vector<double> joint_max_errors_;
/// \brief Pointer to the update event connection.
event::ConnectionPtr updateConnection_;
event::ConnectionPtr sigIntConnection_;
void ImuCallback(ImuPtr& imu_msg);
void GpsCallback(GpsPtr& gps_msg, const int& id);
void GroundtruthCallback(GtPtr& groundtruth_msg);
void LidarCallback(LidarPtr& lidar_msg, const int& id);
void SonarCallback(SonarPtr& sonar_msg, const int& id);
void AirspeedCallback(AirspeedPtr& airspeed_msg, const int& id);
void OpticalFlowCallback(OpticalFlowPtr& opticalFlow_msg);
void IRLockCallback(IRLockPtr& irlock_msg);
void VisionCallback(OdomPtr& odom_msg);
void MagnetometerCallback(MagnetometerPtr& mag_msg);
void BarometerCallback(BarometerPtr& baro_msg);
void WindVelocityCallback(WindPtr& msg);
void SendSensorMessages();
void SendGroundTruth();
void handle_actuator_controls();
void handle_control(double _dt);
bool IsRunning();
void onSigInt();
/**
* @brief Set the MAV_SENSOR_ORIENTATION enum value based on the sensor orientation
*
* @param[in] rootModel The root model where the sensor is attached
* @param[in] u_Xs Unit vector of X-axis sensor in `base_link` frame
* @param[in] sensor_msg The Mavlink DISTANCE_SENSOR message struct
*/
template <class T>
void setMavlinkSensorOrientation(const ignition::math::Vector3d& u_Xs, T& sensor_msg);
/**
* @brief A helper class that allows the creation of multiple subscriptions to sensors.
* It gets the sensor link/joint and creates the subscriptions based on those.
* It also allows to set the initial rotation of the sensor, to allow computing
* the sensor orientation quaternion.
* @details GazeboMsgT The type of the message that will be subscribed to the Gazebo framework.
*/
template <typename GazeboMsgT>
void CreateSensorSubscription(
void (GazeboMavlinkInterface::*fp)(const boost::shared_ptr<GazeboMsgT const>&, const int&),
GazeboMavlinkInterface* ptr, const physics::Joint_V& joints, physics::ModelPtr& nested_model, const std::regex& model);
static const unsigned n_out_max = 16;
double input_offset_[n_out_max]{};
double input_scaling_[n_out_max]{};
std::string joint_control_type_[n_out_max];
std::string gztopic_[n_out_max];
double zero_position_disarmed_[n_out_max]{};
double zero_position_armed_[n_out_max]{};
int input_index_[n_out_max]{};
transport::PublisherPtr joint_control_pub_[n_out_max];
transport::SubscriberPtr imu_sub_{nullptr};
transport::SubscriberPtr opticalFlow_sub_{nullptr};
transport::SubscriberPtr irlock_sub_{nullptr};
transport::SubscriberPtr groundtruth_sub_{nullptr};
transport::SubscriberPtr vision_sub_{nullptr};
transport::SubscriberPtr mag_sub_{nullptr};
transport::SubscriberPtr baro_sub_{nullptr};
transport::SubscriberPtr wind_sub_{nullptr};
Sensor_M sensor_map_{}; // Map of sensor SubscriberPtr, IDs and orientations
std::string imu_sub_topic_{kDefaultImuTopic};
std::string opticalFlow_sub_topic_{kDefaultOpticalFlowTopic};
std::string irlock_sub_topic_{kDefaultIRLockTopic};
std::string groundtruth_sub_topic_{kDefaultGroundtruthTopic};
std::string vision_sub_topic_{kDefaultVisionTopic};
std::string mag_sub_topic_{kDefaultMagTopic};
std::string baro_sub_topic_{kDefaultBarometerTopic};
std::string wind_sub_topic_{kDefaultWindTopic};
std::mutex last_imu_message_mutex_ {};
std::condition_variable last_imu_message_cond_ {};
sensor_msgs::msgs::Imu last_imu_message_;
common::Time last_time_;
common::Time last_imu_time_;
common::Time last_actuator_time_;
double groundtruth_lat_rad_{0.0};
double groundtruth_lon_rad_{0.0};
double groundtruth_altitude_{0.0};
double imu_update_interval_{0.004}; ///< Used for non-lockstep
ignition::math::Vector3d velocity_prev_W_;
ignition::math::Vector3d wind_vel_;
bool close_conn_{false};
double optflow_distance_{0.0};
double sonar_distance;
bool enable_lockstep_{false};
double speed_factor_{1.0};
int64_t previous_imu_seq_{0};
unsigned update_skip_factor_{1};
bool hil_mode_{false};
bool hil_state_level_{false};
};
}