20 #include <geometry_msgs/QuaternionStamped.h> 32 geometry_msgs::QuaternionStamped msg;
33 msg.quaternion.x = attitudeFrdToNed.x();
34 msg.quaternion.y = attitudeFrdToNed.y();
35 msg.quaternion.z = attitudeFrdToNed.z();
36 msg.quaternion.w = attitudeFrdToNed.w();
bool publish(const Eigen::Quaterniond &attitudeFrdToNed)
ros::NodeHandle * node_handler_
AttitudeSensor(ros::NodeHandle *nh, const char *topic, double period)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher publisher_