conversions.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Helen Oleynikova, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13 
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  */
20 
21 // Conversion functions between Eigen types and MAV ROS message types.
22 
23 #ifndef MAV_MSGS_CONVERSIONS_H
24 #define MAV_MSGS_CONVERSIONS_H
25 
26 #include <geometry_msgs/Point.h>
27 #include <geometry_msgs/PoseStamped.h>
28 #include <geometry_msgs/Quaternion.h>
29 #include <geometry_msgs/TransformStamped.h>
30 #include <geometry_msgs/Vector3.h>
31 #include <nav_msgs/Odometry.h>
32 #include <ros/ros.h>
33 #include <trajectory_msgs/MultiDOFJointTrajectory.h>
34 
35 #include "mav_msgs/Actuators.h"
36 #include "mav_msgs/AttitudeThrust.h"
37 #include "mav_msgs/RateThrust.h"
38 #include "mav_msgs/RollPitchYawrateThrust.h"
39 #include "mav_msgs/TorqueThrust.h"
40 #include "mav_msgs/common.h"
43 
44 namespace mav_msgs {
45 
46 inline void eigenAttitudeThrustFromMsg(const AttitudeThrust& msg,
47  EigenAttitudeThrust* attitude_thrust) {
48  assert(attitude_thrust != NULL);
49 
50  attitude_thrust->attitude = quaternionFromMsg(msg.attitude);
51  attitude_thrust->thrust = vector3FromMsg(msg.thrust);
52 }
53 
54 inline void eigenActuatorsFromMsg(const Actuators& msg,
55  EigenActuators* actuators) {
56  assert(actuators != NULL);
57 
58  // Angle of the actuator in [rad].
59  actuators->angles.resize(msg.angles.size());
60  for (unsigned int i = 0; i < msg.angles.size(); ++i) {
61  actuators->angles[i] = msg.angles[i];
62  }
63 
64  // Angular velocities of the actuator in [rad/s].
65  actuators->angular_velocities.resize(msg.angular_velocities.size());
66  for (unsigned int i = 0; i < msg.angular_velocities.size(); ++i) {
67  actuators->angular_velocities[i] = msg.angular_velocities[i];
68  }
69 
70  // Normalized: Everything that does not fit the above, normalized
71  // between [-1 ... 1].
72  actuators->normalized.resize(msg.normalized.size());
73  for (unsigned int i = 0; i < msg.normalized.size(); ++i) {
74  actuators->normalized[i] = msg.normalized[i];
75  }
76 }
77 
78 inline void eigenRateThrustFromMsg(const RateThrust& msg,
79  EigenRateThrust* rate_thrust) {
80  assert(rate_thrust != NULL);
81 
82  rate_thrust->angular_rates = vector3FromMsg(msg.angular_rates);
83  rate_thrust->thrust = vector3FromMsg(msg.thrust);
84 }
85 
86 inline void eigenTorqueThrustFromMsg(const TorqueThrust& msg,
87  EigenTorqueThrust* torque_thrust) {
88  assert(torque_thrust != NULL);
89 
90  torque_thrust->torque = vector3FromMsg(msg.torque);
91  torque_thrust->thrust = vector3FromMsg(msg.thrust);
92 }
93 
95  const RollPitchYawrateThrust& msg,
96  EigenRollPitchYawrateThrust* roll_pitch_yawrate_thrust) {
97  assert(roll_pitch_yawrate_thrust != NULL);
98 
99  roll_pitch_yawrate_thrust->roll = msg.roll;
100  roll_pitch_yawrate_thrust->pitch = msg.pitch;
101  roll_pitch_yawrate_thrust->yaw_rate = msg.yaw_rate;
102  roll_pitch_yawrate_thrust->thrust = vector3FromMsg(msg.thrust);
103 }
104 
105 inline void eigenOdometryFromMsg(const nav_msgs::Odometry& msg,
106  EigenOdometry* odometry) {
107  assert(odometry != NULL);
108  odometry->timestamp_ns = msg.header.stamp.toNSec();
109  odometry->position_W = mav_msgs::vector3FromPointMsg(msg.pose.pose.position);
110  odometry->orientation_W_B =
111  mav_msgs::quaternionFromMsg(msg.pose.pose.orientation);
112  odometry->velocity_B = mav_msgs::vector3FromMsg(msg.twist.twist.linear);
113  odometry->angular_velocity_B =
114  mav_msgs::vector3FromMsg(msg.twist.twist.angular);
115  odometry->pose_covariance_ =
116  Eigen::Map<const Eigen::Matrix<double, 6, 6>>(msg.pose.covariance.data());
117  odometry->twist_covariance_ = Eigen::Map<const Eigen::Matrix<double, 6, 6>>(
118  msg.twist.covariance.data());
119 }
120 
122  const geometry_msgs::TransformStamped& msg,
123  EigenTrajectoryPoint* trajectory_point) {
124  assert(trajectory_point != NULL);
125 
126  ros::Time timestamp = msg.header.stamp;
127 
128  trajectory_point->timestamp_ns = timestamp.toNSec();
129  trajectory_point->position_W = vector3FromMsg(msg.transform.translation);
130  trajectory_point->orientation_W_B = quaternionFromMsg(msg.transform.rotation);
131  trajectory_point->velocity_W.setZero();
132  trajectory_point->angular_velocity_W.setZero();
133  trajectory_point->acceleration_W.setZero();
134  trajectory_point->angular_acceleration_W.setZero();
135  trajectory_point->jerk_W.setZero();
136  trajectory_point->snap_W.setZero();
137 }
138 
139 // 2 versions of this: one for PoseStamped (which fills in the timestamps
140 // correctly and should be used if at all possible), and one for a raw pose
141 // message.
143  const geometry_msgs::Pose& msg, EigenTrajectoryPoint* trajectory_point) {
144  assert(trajectory_point != NULL);
145 
146  trajectory_point->position_W = vector3FromPointMsg(msg.position);
147  trajectory_point->orientation_W_B = quaternionFromMsg(msg.orientation);
148  trajectory_point->velocity_W.setZero();
149  trajectory_point->angular_velocity_W.setZero();
150  trajectory_point->acceleration_W.setZero();
151  trajectory_point->angular_acceleration_W.setZero();
152  trajectory_point->jerk_W.setZero();
153  trajectory_point->snap_W.setZero();
154 }
155 
157  const geometry_msgs::PoseStamped& msg,
158  EigenTrajectoryPoint* trajectory_point) {
159  assert(trajectory_point != NULL);
160 
161  ros::Time timestamp = msg.header.stamp;
162 
163  trajectory_point->timestamp_ns = timestamp.toNSec();
164  eigenTrajectoryPointFromPoseMsg(msg.pose, trajectory_point);
165 }
166 
190  const Eigen::Vector3d& acceleration, const Eigen::Vector3d& jerk,
191  const Eigen::Vector3d& snap, double yaw, double yaw_rate,
192  double yaw_acceleration, double magnitude_of_gravity,
193  Eigen::Quaterniond* orientation, Eigen::Vector3d* acceleration_body,
194  Eigen::Vector3d* angular_velocity_body,
195  Eigen::Vector3d* angular_acceleration_body);
196 
200  const Eigen::Vector3d& acceleration, const Eigen::Vector3d& jerk,
201  const Eigen::Vector3d& snap, double yaw, double yaw_rate,
202  double yaw_acceleration, Eigen::Quaterniond* orientation,
203  Eigen::Vector3d* acceleration_body, Eigen::Vector3d* angular_velocity_body,
204  Eigen::Vector3d* angular_acceleration_body) {
206  acceleration, jerk, snap, yaw, yaw_rate, yaw_acceleration, kGravity,
207  orientation, acceleration_body, angular_velocity_body,
208  angular_acceleration_body);
209 }
210 
214  const EigenTrajectoryPoint& flat_state, double magnitude_of_gravity,
215  EigenMavState* mav_state) {
216  assert(mav_state != NULL);
218  flat_state.acceleration_W, flat_state.jerk_W, flat_state.snap_W,
219  flat_state.getYaw(), flat_state.getYawRate(), flat_state.getYawAcc(),
220  magnitude_of_gravity, &(mav_state->orientation_W_B),
221  &(mav_state->acceleration_B), &(mav_state->angular_velocity_B),
222  &(mav_state->angular_acceleration_B));
223  mav_state->position_W = flat_state.position_W;
224  mav_state->velocity_W = flat_state.velocity_W;
225 }
226 
233  const EigenTrajectoryPoint& flat_state, EigenMavState* mav_state) {
234  EigenMavStateFromEigenTrajectoryPoint(flat_state, kGravity, mav_state);
235 }
236 
238  const Eigen::Vector3d& acceleration, const Eigen::Vector3d& jerk,
239  const Eigen::Vector3d& snap, double yaw, double yaw_rate,
240  double yaw_acceleration, double magnitude_of_gravity,
241  Eigen::Quaterniond* orientation, Eigen::Vector3d* acceleration_body,
242  Eigen::Vector3d* angular_velocity_body,
243  Eigen::Vector3d* angular_acceleration_body) {
244  // Mapping from flat state to full state following to Mellinger [1]:
245  // See [1]: Mellinger, Daniel Warren. "Trajectory generation and control for
246  // quadrotors." (2012), Phd-thesis, p. 15ff.
247  // http://repository.upenn.edu/cgi/viewcontent.cgi?article=1705&context=edissertations
248  //
249  // zb = acc+[0 0 magnitude_of_gravity]';
250  // thrust = norm(zb);
251  // zb = zb / thrust;
252  //
253  // xc = [cos(yaw) sin(yaw) 0]';
254  //
255  // yb = cross(zb, xc);
256  // yb = yb/norm(yb);
257  //
258  // xb = cross(yb, zb);
259  //
260  // q(:,i) = rot2quat([xb yb zb]);
261  //
262  // h_w = 1/thrust*(acc_dot - zb' * acc_dot * zb;
263  //
264  // w(1,i) = -h_w'*yb;
265  // w(2,i) = h_w'*xb;
266  // w(3,i) = yaw_dot*[0 0 1]*zb;
267 
268  assert(orientation != nullptr);
269  assert(acceleration_body != nullptr);
270  assert(angular_velocity_body != nullptr);
271  assert(angular_acceleration_body != nullptr);
272 
273  Eigen::Vector3d xb;
274  Eigen::Vector3d yb;
275  Eigen::Vector3d zb(acceleration);
276 
277  zb[2] += magnitude_of_gravity;
278  const double thrust = zb.norm();
279  const double inv_thrust = 1.0 / thrust;
280  zb = zb * inv_thrust;
281 
282  yb = zb.cross(Eigen::Vector3d(cos(yaw), sin(yaw), 0.0));
283  yb.normalize();
284 
285  xb = yb.cross(zb);
286 
287  const Eigen::Matrix3d R((Eigen::Matrix3d() << xb, yb, zb).finished());
288 
289  const Eigen::Vector3d h_w =
290  inv_thrust * (jerk - double(zb.transpose() * jerk) * zb);
291 
292  *orientation = Eigen::Quaterniond(R);
293  *acceleration_body = R.transpose() * zb * thrust;
294  (*angular_velocity_body)[0] = -h_w.transpose() * yb;
295  (*angular_velocity_body)[1] = h_w.transpose() * xb;
296  (*angular_velocity_body)[2] = yaw_rate * zb[2];
297 
298  // Calculate angular accelerations.
299  const Eigen::Vector3d wcrossz = (*angular_velocity_body).cross(zb);
300  const Eigen::Vector3d wcrosswcrossz = (*angular_velocity_body).cross(wcrossz);
301  const Eigen::Vector3d h_a =
302  inv_thrust * (snap - double(zb.transpose() * snap) * zb) - 2 * wcrossz -
303  wcrosswcrossz + double(zb.transpose() * wcrosswcrossz) * zb;
304 
305  (*angular_acceleration_body)[0] = -h_a.transpose() * yb;
306  (*angular_acceleration_body)[1] = h_a.transpose() * xb;
307  (*angular_acceleration_body)[2] = yaw_acceleration * zb[2];
308 }
309 
311  const trajectory_msgs::MultiDOFJointTrajectoryPoint& msg,
312  EigenTrajectoryPoint* trajectory_point) {
313  assert(trajectory_point != NULL);
314 
315  if (msg.transforms.empty()) {
316  ROS_ERROR("MultiDofJointTrajectoryPoint is empty.");
317  return;
318  }
319 
320  if (msg.transforms.size() > 1) {
321  ROS_WARN(
322  "MultiDofJointTrajectoryPoint message should have one joint, but has "
323  "%lu. Using first joint.",
324  msg.transforms.size());
325  }
326 
327  trajectory_point->time_from_start_ns = msg.time_from_start.toNSec();
328  trajectory_point->position_W = vector3FromMsg(msg.transforms[0].translation);
329  trajectory_point->orientation_W_B =
330  quaternionFromMsg(msg.transforms[0].rotation);
331  if (msg.velocities.size() > 0) {
332  trajectory_point->velocity_W = vector3FromMsg(msg.velocities[0].linear);
333  trajectory_point->angular_velocity_W =
334  vector3FromMsg(msg.velocities[0].angular);
335  } else {
336  trajectory_point->velocity_W.setZero();
337  trajectory_point->angular_velocity_W.setZero();
338  }
339  if (msg.accelerations.size() > 0) {
340  trajectory_point->acceleration_W =
341  vector3FromMsg(msg.accelerations[0].linear);
342  trajectory_point->angular_acceleration_W =
343  vector3FromMsg(msg.accelerations[0].angular);
344  } else {
345  trajectory_point->acceleration_W.setZero();
346  trajectory_point->angular_acceleration_W.setZero();
347  }
348  trajectory_point->jerk_W.setZero();
349  trajectory_point->snap_W.setZero();
350 }
351 
353  const trajectory_msgs::MultiDOFJointTrajectory& msg,
354  EigenTrajectoryPointVector* trajectory) {
355  assert(trajectory != NULL);
356  trajectory->clear();
357  for (const auto& msg_point : msg.points) {
358  EigenTrajectoryPoint point;
359  eigenTrajectoryPointFromMsg(msg_point, &point);
360  trajectory->push_back(point);
361  }
362 }
363 
365  const trajectory_msgs::MultiDOFJointTrajectory& msg,
366  EigenTrajectoryPointDeque* trajectory) {
367  assert(trajectory != NULL);
368  trajectory->clear();
369  for (const auto& msg_point : msg.points) {
370  EigenTrajectoryPoint point;
371  eigenTrajectoryPointFromMsg(msg_point, &point);
372  trajectory->push_back(point);
373  }
374 }
375 
376 // In all these conversions, client is responsible for filling in message
377 // header.
378 inline void msgActuatorsFromEigen(const EigenActuators& actuators,
379  Actuators* msg) {
380  assert(msg != NULL);
381 
382  msg->angles.resize(actuators.angles.size());
383  for (unsigned int i = 0; i < actuators.angles.size(); ++i) {
384  msg->angles[i] = actuators.angles[i];
385  }
386 
387  msg->angular_velocities.resize(actuators.angular_velocities.size());
388  for (unsigned int i = 0; i < actuators.angular_velocities.size(); ++i) {
389  msg->angular_velocities[i] = actuators.angular_velocities[i];
390  }
391 
392  msg->normalized.resize(actuators.normalized.size());
393  for (unsigned int i = 0; i < actuators.normalized.size(); ++i) {
394  msg->normalized[i] = actuators.normalized[i];
395  }
396 }
397 
399  const EigenAttitudeThrust& attitude_thrust, AttitudeThrust* msg) {
400  assert(msg != NULL);
401  quaternionEigenToMsg(attitude_thrust.attitude, &msg->attitude);
402  vectorEigenToMsg(attitude_thrust.thrust, &msg->thrust);
403 }
404 
405 inline void msgRateThrustFromEigen(EigenRateThrust& rate_thrust,
406  RateThrust* msg) {
407  assert(msg != NULL);
408  vectorEigenToMsg(rate_thrust.angular_rates, &msg->angular_rates);
409  vectorEigenToMsg(rate_thrust.thrust, &msg->thrust);
410 }
411 
412 inline void msgTorqueThrustFromEigen(EigenTorqueThrust& torque_thrust,
413  TorqueThrust* msg) {
414  assert(msg != NULL);
415  vectorEigenToMsg(torque_thrust.torque, &msg->torque);
416  vectorEigenToMsg(torque_thrust.thrust, &msg->thrust);
417 }
418 
420  const EigenRollPitchYawrateThrust& roll_pitch_yawrate_thrust,
421  RollPitchYawrateThrust* msg) {
422  assert(msg != NULL);
423  msg->roll = roll_pitch_yawrate_thrust.roll;
424  msg->pitch = roll_pitch_yawrate_thrust.pitch;
425  msg->yaw_rate = roll_pitch_yawrate_thrust.yaw_rate;
426  vectorEigenToMsg(roll_pitch_yawrate_thrust.thrust, &msg->thrust);
427 }
428 
429 inline void msgOdometryFromEigen(const EigenOdometry& odometry,
430  nav_msgs::Odometry* msg) {
431  assert(msg != NULL);
432 
433  if (odometry.timestamp_ns >= 0) {
434  msg->header.stamp.fromNSec(odometry.timestamp_ns);
435  }
436  pointEigenToMsg(odometry.position_W, &msg->pose.pose.position);
437  quaternionEigenToMsg(odometry.orientation_W_B, &msg->pose.pose.orientation);
438 
439  vectorEigenToMsg(odometry.velocity_B, &msg->twist.twist.linear);
440  vectorEigenToMsg(odometry.angular_velocity_B, &msg->twist.twist.angular);
441 }
442 
443 // WARNING: discards all derivatives, etc.
445  const EigenTrajectoryPoint& trajectory_point,
446  geometry_msgs::PoseStamped* msg) {
447  if (trajectory_point.timestamp_ns >= 0) {
448  msg->header.stamp.fromNSec(trajectory_point.timestamp_ns);
449  }
450  pointEigenToMsg(trajectory_point.position_W, &msg->pose.position);
451  quaternionEigenToMsg(trajectory_point.orientation_W_B,
452  &msg->pose.orientation);
453 }
454 
456  const EigenTrajectoryPoint& trajectory_point,
457  trajectory_msgs::MultiDOFJointTrajectoryPoint* msg) {
458  assert(msg != NULL);
459 
460  msg->time_from_start.fromNSec(trajectory_point.time_from_start_ns);
461  msg->transforms.resize(1);
462  msg->velocities.resize(1);
463  msg->accelerations.resize(1);
464 
465  vectorEigenToMsg(trajectory_point.position_W,
466  &msg->transforms[0].translation);
467  quaternionEigenToMsg(trajectory_point.orientation_W_B,
468  &msg->transforms[0].rotation);
469  vectorEigenToMsg(trajectory_point.velocity_W, &msg->velocities[0].linear);
470  vectorEigenToMsg(trajectory_point.angular_velocity_W,
471  &msg->velocities[0].angular);
472  vectorEigenToMsg(trajectory_point.acceleration_W,
473  &msg->accelerations[0].linear);
474 }
475 
477  const EigenTrajectoryPoint& trajectory_point, const std::string& link_name,
478  trajectory_msgs::MultiDOFJointTrajectory* msg) {
479  assert(msg != NULL);
480  trajectory_msgs::MultiDOFJointTrajectoryPoint point_msg;
481  msgMultiDofJointTrajectoryPointFromEigen(trajectory_point, &point_msg);
482 
483  msg->joint_names.clear();
484  msg->points.clear();
485  msg->joint_names.push_back(link_name);
486  msg->points.push_back(point_msg);
487 }
488 
490  const EigenTrajectoryPoint& trajectory_point,
491  trajectory_msgs::MultiDOFJointTrajectory* msg) {
492  msgMultiDofJointTrajectoryFromEigen(trajectory_point, "base_link", msg);
493 }
494 
495 // Convenience method to quickly create a trajectory from a single waypoint.
497  const Eigen::Vector3d& position, double yaw,
498  trajectory_msgs::MultiDOFJointTrajectory* msg) {
499  assert(msg != NULL);
500 
501  EigenTrajectoryPoint point;
502  point.position_W = position;
503  point.setFromYaw(yaw);
504 
506 }
507 
509  const EigenTrajectoryPointVector& trajectory, const std::string& link_name,
510  trajectory_msgs::MultiDOFJointTrajectory* msg) {
511  assert(msg != NULL);
512 
513  if (trajectory.empty()) {
514  ROS_ERROR("EigenTrajectoryPointVector is empty.");
515  return;
516  }
517 
518  msg->joint_names.clear();
519  msg->joint_names.push_back(link_name);
520  msg->points.clear();
521 
522  for (const auto& trajectory_point : trajectory) {
523  trajectory_msgs::MultiDOFJointTrajectoryPoint point_msg;
524  msgMultiDofJointTrajectoryPointFromEigen(trajectory_point, &point_msg);
525  msg->points.push_back(point_msg);
526  }
527 }
528 
530  const EigenTrajectoryPointVector& trajectory,
531  trajectory_msgs::MultiDOFJointTrajectory* msg) {
532  msgMultiDofJointTrajectoryFromEigen(trajectory, "base_link", msg);
533 }
534 
536  const EigenTrajectoryPointDeque& trajectory, const std::string& link_name,
537  trajectory_msgs::MultiDOFJointTrajectory* msg) {
538  assert(msg != NULL);
539 
540  if (trajectory.empty()) {
541  ROS_ERROR("EigenTrajectoryPointVector is empty.");
542  return;
543  }
544 
545  msg->joint_names.clear();
546  msg->joint_names.push_back(link_name);
547  msg->points.clear();
548 
549  for (const auto& trajectory_point : trajectory) {
550  trajectory_msgs::MultiDOFJointTrajectoryPoint point_msg;
551  msgMultiDofJointTrajectoryPointFromEigen(trajectory_point, &point_msg);
552  msg->points.push_back(point_msg);
553  }
554 }
555 
557  const EigenTrajectoryPointDeque& trajectory,
558  trajectory_msgs::MultiDOFJointTrajectory* msg) {
559  msgMultiDofJointTrajectoryFromEigen(trajectory, "base_link", msg);
560 }
561 
562 } // end namespace mav_msgs
563 
564 #endif // MAV_MSGS_CONVERSIONS_H
void quaternionEigenToMsg(const Eigen::Quaterniond &eigen, geometry_msgs::Quaternion *msg)
Definition: common.h:90
const double kGravity
void eigenTrajectoryPointFromMsg(const trajectory_msgs::MultiDOFJointTrajectoryPoint &msg, EigenTrajectoryPoint *trajectory_point)
Definition: conversions.h:310
void eigenTrajectoryPointDequeFromMsg(const trajectory_msgs::MultiDOFJointTrajectory &msg, EigenTrajectoryPointDeque *trajectory)
Definition: conversions.h:364
void msgOdometryFromEigen(const EigenOdometry &odometry, nav_msgs::Odometry *msg)
Definition: conversions.h:429
Eigen::VectorXd normalized
Eigen::Vector3d position_W
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int64_t timestamp_ns
void msgRollPitchYawrateThrustFromEigen(const EigenRollPitchYawrateThrust &roll_pitch_yawrate_thrust, RollPitchYawrateThrust *msg)
Definition: conversions.h:419
Eigen::Vector3d vector3FromMsg(const geometry_msgs::Vector3 &msg)
Definition: common.h:53
Eigen::Vector3d velocity_B
void msgMultiDofJointTrajectoryPointFromEigen(const EigenTrajectoryPoint &trajectory_point, trajectory_msgs::MultiDOFJointTrajectoryPoint *msg)
Definition: conversions.h:455
Eigen::Matrix< double, 6, 6 > twist_covariance_
void msgMultiDofJointTrajectoryFromEigen(const EigenTrajectoryPoint &trajectory_point, const std::string &link_name, trajectory_msgs::MultiDOFJointTrajectory *msg)
Definition: conversions.h:476
Eigen::Matrix< double, 6, 6 > pose_covariance_
Eigen::Quaterniond orientation_W_B
uint64_t toNSec() const
void EigenMavStateFromEigenTrajectoryPoint(const Eigen::Vector3d &acceleration, const Eigen::Vector3d &jerk, const Eigen::Vector3d &snap, double yaw, double yaw_rate, double yaw_acceleration, double magnitude_of_gravity, Eigen::Quaterniond *orientation, Eigen::Vector3d *acceleration_body, Eigen::Vector3d *angular_velocity_body, Eigen::Vector3d *angular_acceleration_body)
Computes the MAV state (position, velocity, attitude, angular velocity, angular acceleration) from th...
Definition: conversions.h:237
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d angular_rates
void eigenOdometryFromMsg(const nav_msgs::Odometry &msg, EigenOdometry *odometry)
Definition: conversions.h:105
void eigenTrajectoryPointFromPoseMsg(const geometry_msgs::Pose &msg, EigenTrajectoryPoint *trajectory_point)
Definition: conversions.h:142
Eigen::VectorXd angular_velocities
void eigenTrajectoryPointVectorFromMsg(const trajectory_msgs::MultiDOFJointTrajectory &msg, EigenTrajectoryPointVector *trajectory)
Definition: conversions.h:352
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int64_t timestamp_ns
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::VectorXd angles
void eigenAttitudeThrustFromMsg(const AttitudeThrust &msg, EigenAttitudeThrust *attitude_thrust)
Definition: conversions.h:46
Eigen::Quaterniond orientation_W_B
Eigen::Vector3d position_W
void msgPoseStampedFromEigenTrajectoryPoint(const EigenTrajectoryPoint &trajectory_point, geometry_msgs::PoseStamped *msg)
Definition: conversions.h:444
Eigen::Vector3d angular_acceleration_B
void eigenTrajectoryPointFromTransformMsg(const geometry_msgs::TransformStamped &msg, EigenTrajectoryPoint *trajectory_point)
Definition: conversions.h:121
void eigenRateThrustFromMsg(const RateThrust &msg, EigenRateThrust *rate_thrust)
Definition: conversions.h:78
void msgTorqueThrustFromEigen(EigenTorqueThrust &torque_thrust, TorqueThrust *msg)
Definition: conversions.h:412
void eigenActuatorsFromMsg(const Actuators &msg, EigenActuators *actuators)
Definition: conversions.h:54
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Quaterniond attitude
void vectorEigenToMsg(const Eigen::Vector3d &eigen, geometry_msgs::Vector3 *msg)
Definition: common.h:74
Container holding the state of a MAV: position, velocity, attitude and angular velocity. In addition, holds the acceleration expressed in body coordinates, which is what the accelerometer usually measures.
void msgMultiDofJointTrajectoryFromPositionYaw(const Eigen::Vector3d &position, double yaw, trajectory_msgs::MultiDOFJointTrajectory *msg)
Definition: conversions.h:496
Eigen::Vector3d angular_velocity_B
Eigen::Vector3d angular_acceleration_W
Eigen::Quaterniond quaternionFromMsg(const geometry_msgs::Quaternion &msg)
Definition: common.h:61
Eigen::Quaterniond orientation_W_B
Eigen::Vector3d vector3FromPointMsg(const geometry_msgs::Point &msg)
Definition: common.h:57
void msgAttitudeThrustFromEigen(const EigenAttitudeThrust &attitude_thrust, AttitudeThrust *msg)
Definition: conversions.h:398
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d torque
void eigenTorqueThrustFromMsg(const TorqueThrust &msg, EigenTorqueThrust *torque_thrust)
Definition: conversions.h:86
Eigen::Vector3d velocity_W
void eigenRollPitchYawrateThrustFromMsg(const RollPitchYawrateThrust &msg, EigenRollPitchYawrateThrust *roll_pitch_yawrate_thrust)
Definition: conversions.h:94
Eigen::Vector3d angular_velocity_B
void pointEigenToMsg(const Eigen::Vector3d &eigen, geometry_msgs::Point *msg)
Definition: common.h:82
Eigen::Vector3d acceleration_B
void msgRateThrustFromEigen(EigenRateThrust &rate_thrust, RateThrust *msg)
Definition: conversions.h:405
void msgActuatorsFromEigen(const EigenActuators &actuators, Actuators *msg)
Definition: conversions.h:378


mav_msgs
Author(s): Simon Lynen, Markus Achtelik, Pascal Gohl, Sammy Omari, Michael Burri, Fadri Furrer, Helen Oleynikova, Mina Kamel, Karen Bodie, Rik Bähnemann
autogenerated on Sat Jun 15 2019 19:55:13