|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
19 #ifndef GROUND_DDS_ROS_BRIDGE_RAPID_POSITION_H_
20 #define GROUND_DDS_ROS_BRIDGE_RAPID_POSITION_H_
28 #include "ff_msgs/EkfState.h"
30 #include "dds_msgs/AstrobeeConstants.h"
31 #include "dds_msgs/EkfStateSupport.h"
38 const std::string& pub_topic,
39 const ros::NodeHandle &nh,
40 const unsigned int queue_size = 10);
43 const rapid::Transform3D& transform);
45 void CopyVec3D(geometry_msgs::Vector3& vec_out,
46 const rapid::Vec3d& vec_in);
49 void operator() (rapid::ext::astrobee::EkfState
const* rapid_ekf_state);
54 #endif // GROUND_DDS_ROS_BRIDGE_RAPID_POSITION_H_
Definition: rapid_position.h:35
Definition: generic_rapid_msg_ros_pub.h:36
base class for rapid subscriber to ros publisher
Definition: rapid_sub_ros_pub.h:42
RapidPositionToRos(const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size=10)
Definition: rapid_position.cc:23
void operator()(rapid::ext::astrobee::EkfState const *rapid_ekf_state)
Definition: rapid_position.cc:73
void CopyTransform3D(geometry_msgs::Pose &pose, const rapid::Transform3D &transform)
Definition: rapid_position.cc:54
void CopyVec3D(geometry_msgs::Vector3 &vec_out, const rapid::Vec3d &vec_in)
Definition: rapid_position.cc:66