multiwii_node.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 
3 #include <dynamic_reconfigure/server.h>
4 #include <multiwii/UpdateRatesConfig.h>
5 
6 #include <std_msgs/UInt16.h>
7 #include <std_msgs/UInt32.h>
8 #include <std_msgs/UInt8MultiArray.h>
9 #include <std_msgs/Bool.h>
10 #include <std_msgs/Float64.h>
11 
12 #include <geometry_msgs/PoseStamped.h>
13 #include <geometry_msgs/Vector3.h>
14 
15 #include <sensor_msgs/BatteryState.h>
16 #include <sensor_msgs/Imu.h>
17 #include <sensor_msgs/MagneticField.h>
18 
19 #include <mavros_msgs/RCIn.h>
20 #include <mavros_msgs/RCOut.h>
21 #include <mavros_msgs/OverrideRCIn.h>
22 #include <mavros_msgs/ActuatorControl.h>
23 #include <mavros_msgs/CommandBool.h>
24 
26 
27 #include <msp/FlightController.hpp>
28 #include <msp/msp_msg.hpp>
29 
30 #include <Eigen/Geometry>
31 
32 double deg2rad(const double deg) {
33  return deg/180.0 * M_PI;
34 }
35 
36 double rad2deg(const double rad) {
37  return rad/M_PI * 180.0;
38 }
39 
40 class MultiWiiNode {
41 private:
44 
45  float acc_1g;
46  float gyro_unit;
47  float magn_gain;
48  float si_unit_1g;
49  std::string tf_base_frame;
50 
51  dynamic_reconfigure::Server<multiwii::UpdateRatesConfig> dyn_conf_srv;
52 
64 
68 
70 
71 public:
73  nh = ros::NodeHandle("~");
74  // configure
75  fcu = new fcu::FlightController();
76 
77  float std_grav;
78  if(nh.getParam("standard_gravity", std_grav))
79  this->si_unit_1g = std_grav;
80  else
81  ROS_ERROR("Parameter 'standard_gravity' not set.");
82 
83  float acc_1g;
84  if(nh.getParam("acc_1g", acc_1g))
85  this->acc_1g = acc_1g;
86  else
87  ROS_ERROR("Parameter 'acc_1g' not set.");
88 
89  float gyro_unit;
90  if(nh.getParam("gyro_unit", gyro_unit))
91  this->gyro_unit = gyro_unit;
92  else
93  ROS_ERROR("Parameter 'gyro_unit' not set.");
94 
95  float magn_gain;
96  if(nh.getParam("magn_gain", magn_gain))
97  this->magn_gain = magn_gain;
98  else
99  ROS_ERROR("Parameter 'magn_gain' not set.");
100 
101  // Get the base frame to which the TF is published
102  nh.param<std::string>("tf_base_frame", this->tf_base_frame, "map");
103  }
104 
106  delete fcu;
107  }
108 
110  return *fcu;
111  }
112 
113  void setup() {
114  std::string device;
115  int baudrate = 115200;
116  if(nh.getParam("device", device)) {
117  if(!nh.getParam("baudrate", baudrate)) {
118  ROS_ERROR("Parameter 'baudrate' not set. Using default baudrate of %i", baudrate);
119  }
120  else {
121  if(baudrate<=0) {
122  ROS_ERROR("'baudrate' must be positive!");
123  baudrate = 115200;
124  }
125  }
126  ROS_INFO("Connected to FCU at %s", device.c_str());
127  }
128  else {
129  ROS_ERROR("Parameter 'device' not set.");
130  }
131 
132  fcu->connect(device, uint(baudrate));
133 
134  // publisher
135  imu_pub = nh.advertise<sensor_msgs::Imu>("imu/data", 1);
136  magn_pub = nh.advertise<sensor_msgs::MagneticField>("imu/mag", 1);
137  pose_stamped_pub = nh.advertise<geometry_msgs::PoseStamped>("local_position/pose", 1);
138  rpy_pub = nh.advertise<geometry_msgs::Vector3>("rpy", 1);
139  rc_in_pub = nh.advertise<mavros_msgs::RCIn>("rc/in", 1);
140  servo_pub = nh.advertise<mavros_msgs::RCOut>("rc/servo", 1);
141  motors_pub = nh.advertise<mavros_msgs::RCOut>("motors", 1);
142  battery_pub = nh.advertise<sensor_msgs::BatteryState>("battery",1);
143  heading_pub = nh.advertise<std_msgs::Float64>("global_position/compass_hdg",1);
144  altitude_pub = nh.advertise<std_msgs::Float64>("global_position/rel_alt",1);
145  sonar_altitude_pub = nh.advertise<std_msgs::Float64>("global_position/sonar_alt", 1);
146 
147  // subscriber
148  rc_in_sub = nh.subscribe("rc/override", 1, &MultiWiiNode::rc_override_AERT1234, this); // AERT1234
149  rc_in_sub2 = nh.subscribe("rc/override/raw", 1, &MultiWiiNode::rc_override_raw, this); // raw channel order
150  motor_control_sub = nh.subscribe("actuator_control", 1, &MultiWiiNode::motor_control, this);
151  }
152 
158  // dynamic configure
159  dyn_conf_srv.setCallback(boost::bind(&MultiWiiNode::dynconf_callback, this, _1, _2));
160  }
161 
162  void dynconf_callback(multiwii::UpdateRatesConfig &config, uint32_t /*level*/) {
163  // define map with matching update rate per message ID
164  const std::map<msp::ID, double> msp_rates = {
165  {msp::ID::MSP_RAW_IMU, config.MSP_RAW_IMU},
166  {msp::ID::MSP_ALTITUDE, config.MSP_ALTITUDE},
167  {msp::ID::MSP_ATTITUDE, config.MSP_ATTITUDE},
168  {msp::ID::MSP_RC, config.MSP_RC},
169  {msp::ID::MSP_SERVO, config.MSP_SERVO},
170  {msp::ID::MSP_MOTOR, config.MSP_MOTOR},
171  {msp::ID::MSP_ANALOG, config.MSP_ANALOG},
172  {msp::ID::MSP_SONAR_ALTITUDE, config.MSP_SONAR_ALTITUDE},
173  };
174 
175  // apply update
176  for(const auto& r : msp_rates) {
177  if(fcu->hasSubscription(r.first)) {
178  fcu->getSubscription(r.first)->setTimerFrequency(r.second);
179  }
180  }
181  }
182 
183 
186 
187  void onImu(const msp::msg::RawImu &imu) {
190 
191  sensor_msgs::Imu imu_msg;
192  imu_msg.header.stamp = ros::Time::now();
193  imu_msg.header.frame_id = "multiwii";
194 
195  // linear acceleration in m/s²
196  imu_msg.linear_acceleration.x = imu.acc[0];
197  imu_msg.linear_acceleration.y = imu.acc[1];
198  imu_msg.linear_acceleration.z = imu.acc[2];
199 
200  // angular velocity in rad/s
201  imu_msg.angular_velocity.x = deg2rad(imu.gyro[0]);
202  imu_msg.angular_velocity.y = deg2rad(imu.gyro[1]);
203  imu_msg.angular_velocity.z = deg2rad(imu.gyro[2]);
204 
205  // rotation from direction of acceleration and magnetic field
206  const Eigen::Vector3d magn(imu.mag[0], imu.mag[1], imu.mag[2]);
207  const Eigen::Vector3d lin_acc(imu.acc[0], imu.acc[1], imu.acc[2]);
208 
209  // http://www.camelsoftware.com/2016/02/20/imu-maths/
210  Eigen::Matrix3d rot;
211  rot.col(0) = lin_acc.cross(magn).cross(lin_acc).normalized();
212  rot.col(1) = lin_acc.cross(magn).normalized();
213  rot.col(2) = lin_acc.normalized();
214 
215  const Eigen::Quaterniond orientation(rot);
216  imu_msg.orientation.x = orientation.x();
217  imu_msg.orientation.y = orientation.y();
218  imu_msg.orientation.z = orientation.z();
219  imu_msg.orientation.w = orientation.w();
220 
221  imu_pub.publish(imu_msg);
222 
225 
226  sensor_msgs::MagneticField mag_msg;
227  mag_msg.header.stamp = ros::Time::now();
228 
229  // magnetic field in uT
230  mag_msg.magnetic_field.x = imu.mag[0];
231  mag_msg.magnetic_field.y = imu.mag[1];
232  mag_msg.magnetic_field.z = imu.mag[2];
233  magn_pub.publish(mag_msg);
234 
237 
238  std_msgs::Float64 heading;
239  heading.data = rad2deg(std::atan2(double(imu.mag[0]), double(imu.mag[1])));
240  heading_pub.publish(heading);
241  }
242 
243  void onAttitude(const msp::msg::Attitude &attitude) {
244  // r,p,y to rotation matrix
245  Eigen::Matrix3f rot;
246  rot = Eigen::AngleAxisf(deg2rad(attitude.roll), Eigen::Vector3f::UnitX())
247  * Eigen::AngleAxisf(deg2rad(attitude.pitch), Eigen::Vector3f::UnitY())
248  * Eigen::AngleAxisf(deg2rad(attitude.yaw), Eigen::Vector3f::UnitZ());
249 
250  const Eigen::Quaternionf quat(rot);
251 
252  geometry_msgs::PoseStamped pose_stamped;
253  pose_stamped.header.stamp = ros::Time::now();
254  pose_stamped.header.frame_id = "multiwii";
255  pose_stamped.pose.orientation.x = quat.x();
256  pose_stamped.pose.orientation.y = quat.y();
257  pose_stamped.pose.orientation.z = quat.z();
258  pose_stamped.pose.orientation.w = quat.w();
259 
260  pose_stamped_pub.publish(pose_stamped);
261 
263  // Broadcast transform to relate multiwii transformation to the base frame
264  // Convert attitude values to quaternion
265  tf::Quaternion multiwii_quaternion;
266  multiwii_quaternion.setRPY(deg2rad(attitude.roll), deg2rad(attitude.pitch), deg2rad(attitude.yaw));
267  // Pack attitude into tf::Transform
268  tf::Transform multiwii_transform;
269  multiwii_transform.setRotation(multiwii_quaternion);
270  multiwii_transform.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
271  // Broadcast as tf::StampedTransform
272  tf_broadcaster.sendTransform(tf::StampedTransform(multiwii_transform, ros::Time::now(), "multiwii_cartesian", "multiwii"));
273 
274  geometry_msgs::Vector3 rpy;
275  rpy.x = attitude.roll;
276  rpy.y = attitude.pitch;
277  rpy.z = attitude.yaw;
278  rpy_pub.publish(rpy);
279  }
280 
281  void onAltitude(const msp::msg::Altitude &altitude) {
282  std_msgs::Float64 alt; // altitude in meter
283  alt.data = altitude.altitude;
284  altitude_pub.publish(alt);
285 
287  // Broadcast transform to relate multiwii transformation to the base frame
288  // Pack attitude into tf::Transform
289  tf::Quaternion multiwii_quaternion(0.0, 0.0, 0.0, 1.0);
290  tf::Transform multiwii_transform;
291  multiwii_transform.setRotation(multiwii_quaternion);
292  multiwii_transform.setOrigin(tf::Vector3(0.0, 0.0, altitude.altitude));
293  // Broadcast as tf::StampedTransform
294  tf_broadcaster.sendTransform(tf::StampedTransform(multiwii_transform, ros::Time::now(), this->tf_base_frame, "multiwii_cartesian"));
295  }
296 
297  void onRc(const msp::msg::Rc &rc) {
298  mavros_msgs::RCIn rc_msg;
299  rc_msg.header.stamp = ros::Time::now();
300  rc_msg.channels = rc.channels;
301 
302  rc_in_pub.publish(rc_msg);
303  }
304 
305  void onServo(const msp::msg::Servo &servo) {
306  mavros_msgs::RCOut rc;
307  for(const uint16_t s : servo.servo) {
308  rc.channels.push_back(s);
309  }
310  servo_pub.publish(rc);
311  }
312 
313  void onMotor(const msp::msg::Motor &motor) {
314  mavros_msgs::RCOut motor_out;
315  for(const uint16_t m : motor.motor) {
316  motor_out.channels.push_back(m);
317  }
318  motors_pub.publish(motor_out);
319  }
320 
321  void onAnalog(const msp::msg::Analog &analog) {
322  sensor_msgs::BatteryState battery;
323  battery.header.stamp = ros::Time::now();
324  battery.voltage = analog.vbat;
325  battery.current = analog.amperage;
326 
327  battery_pub.publish(battery);
328  }
329 
330  void onSonarAltitude(const msp::msg::SonarAltitude &sonar_altitude) {
331  std_msgs::Float64 alt;
332  alt.data = sonar_altitude.altitude_cm;
333  sonar_altitude_pub.publish(alt);
334 
336  // Broadcast transform to relate multiwii transformation to the base frame
337  // Pack attitude into tf::Transform
338  tf::Quaternion multiwii_quaternion(0.0, 0.0, 0.0, 1.0);
339  tf::Transform multiwii_transform;
340  multiwii_transform.setRotation(multiwii_quaternion);
341  multiwii_transform.setOrigin(tf::Vector3(0.0, 0.0, sonar_altitude.altitude_cm));
342  // Broadcast as tf::StampedTransform
343  tf_broadcaster.sendTransform(tf::StampedTransform(multiwii_transform, ros::Time::now(), this->tf_base_frame, "multiwii_cartesian"));
344  }
345 
346 
349 
350  void rc_override_AERT1234(const mavros_msgs::OverrideRCIn &rc) {
351  fcu->setRc(rc.channels[0], rc.channels[1], rc.channels[2], rc.channels[3],
352  rc.channels[4], rc.channels[5], rc.channels[6], rc.channels[7]);
353  }
354 
355  void rc_override_raw(const mavros_msgs::OverrideRCIn &rc) {
356  std::vector<uint16_t> channels;
357  for(const uint16_t c : rc.channels) { channels.push_back(c); }
358  fcu->setRc(channels);
359  }
360 
361  void motor_control(const mavros_msgs::ActuatorControl &motors) {
362  // ActuatorControl::controls contains normed values in range [-1,+1],
363  // negative values are for reversing the motor spinning direction.
364  // We will ignore reversed motor direction and the final motor value
365  // becomes: 1000 + abs(m)*1000
366 
367  std::array<uint16_t,msp::msg::N_MOTOR> motor_values;
368  for(uint i(0); i<motor_values.size(); i++) {
369  motor_values[i] = 1000+abs(motors.controls[i]*1000);
370  }
371 
372  fcu->setMotors(motor_values);
373  }
374 };
375 
376 int main(int argc, char **argv) {
377  ros::init(argc, argv, "MultiWii");
378 
379  MultiWiiNode node;
380 
381  // setup FCU, register publisher
382  node.setup();
383 
384  ROS_INFO("MSP ready");
385  std::cout<<"MSP ready"<<std::endl;
386 
387  node.fc().subscribe(&MultiWiiNode::onImu, &node);
388  node.fc().subscribe(&MultiWiiNode::onAttitude, &node);
389  node.fc().subscribe(&MultiWiiNode::onAltitude, &node);
390  node.fc().subscribe(&MultiWiiNode::onRc, &node);
391  node.fc().subscribe(&MultiWiiNode::onServo, &node);
392  node.fc().subscribe(&MultiWiiNode::onMotor, &node);
393  node.fc().subscribe(&MultiWiiNode::onAnalog, &node);
395 
396  // register callback for dynamic configuration
397  // - update rates for MSP subscriber
398  // - main ROS node loop rate
400 
401  ros::spin();
402 
403  ros::shutdown();
404 }
void onMotor(const msp::msg::Motor &motor)
ros::Publisher rpy_pub
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
Value< float > altitude
double deg2rad(const double deg)
ros::Subscriber rc_in_sub
ros::Publisher pose_stamped_pub
void publish(const boost::shared_ptr< M > &message) const
std::array< uint16_t, N_SERVO > servo
unsigned int uint
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber motor_control_sub
std::vector< uint16_t > channels
Value< int16_t > pitch
XmlRpcServer s
ros::Publisher servo_pub
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Value< int16_t > roll
void onImu(const msp::msg::RawImu &imu)
callbacks for published messages
tf::TransformBroadcaster tf_broadcaster
std::array< Value< int16_t >, 3 > mag
bool hasSubscription(const msp::ID &id) const
void onAttitude(const msp::msg::Attitude &attitude)
ros::Publisher imu_pub
void onServo(const msp::msg::Servo &servo)
ROSCPP_DECL void spin(Spinner &spinner)
void motor_control(const mavros_msgs::ActuatorControl &motors)
Value< float > amperage
Value< int16_t > yaw
int main(int argc, char **argv)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
ros::Publisher heading_pub
void onSonarAltitude(const msp::msg::SonarAltitude &sonar_altitude)
#define ROS_INFO(...)
Value< float > vbat
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::array< Value< int16_t >, 3 > gyro
ros::Publisher battery_pub
void sendTransform(const StampedTransform &transform)
bool setMotors(const std::array< uint16_t, msp::msg::N_MOTOR > &motor_values)
double rad2deg(const double rad)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::array< uint16_t, N_MOTOR > motor
std::array< Value< int16_t >, 3 > acc
ros::Publisher altitude_pub
void rc_override_raw(const mavros_msgs::OverrideRCIn &rc)
std::shared_ptr< msp::client::SubscriptionBase > getSubscription(const msp::ID &id)
bool setRc(const uint16_t roll, const uint16_t pitch, const uint16_t yaw, const uint16_t throttle, const uint16_t aux1=1000, const uint16_t aux2=1000, const uint16_t aux3=1000, const uint16_t aux4=1000, const std::vector< uint16_t > auxs=std::vector< uint16_t >())
ros::Subscriber rc_in_sub2
void onAnalog(const msp::msg::Analog &analog)
void setDynamicConfigureCallback()
setDynamicConfigureCallback set the callback This will call the callback once for initialisation ...
fcu::FlightController & fc() const
ros::Publisher rc_in_pub
void onRc(const msp::msg::Rc &rc)
ros::Publisher vis_pub
bool getParam(const std::string &key, std::string &s) const
bool connect(const std::string &device, const size_t baudrate=115200, const double &timeout=0.0, const bool print_info=false)
static Time now()
ros::Publisher sonar_altitude_pub
ros::NodeHandle nh
ROSCPP_DECL void shutdown()
ros::Publisher magn_pub
std::shared_ptr< msp::client::SubscriptionBase > subscribe(void(C::*callback)(const T &), C *context, const double tp=0.0)
Value< uint32_t > altitude_cm
void dynconf_callback(multiwii::UpdateRatesConfig &config, uint32_t)
fcu::FlightController * fcu
#define ROS_ERROR(...)
std::string tf_base_frame
ros::Publisher motors_pub
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
void rc_override_AERT1234(const mavros_msgs::OverrideRCIn &rc)
callbacks for subscribed messages
dynamic_reconfigure::Server< multiwii::UpdateRatesConfig > dyn_conf_srv
void onAltitude(const msp::msg::Altitude &altitude)


multiwii
Author(s): Christian Rauch
autogenerated on Fri Jul 17 2020 03:36:13