|
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 DDS_ROS_BRIDGE_RAPID_EKF_ROS_EKF_H_
20 #define DDS_ROS_BRIDGE_RAPID_EKF_ROS_EKF_H_
24 #include <ros/assert.h>
30 #include "dds_ros_bridge/rapid_sub_ros_pub.h"
31 #include "dds_ros_bridge/util.h"
33 #include "ff_msgs/EkfState.h"
35 #include "dds_msgs/AstrobeeConstants.h"
37 #include "knDds/DdsTypedSupplier.h"
39 #include "dds_msgs/EkfStateSupport.h"
41 #include "rapidDds/RapidConstants.h"
43 #include "rapidUtil/RapidHelper.h"
50 const std::string& subscribe_partition,
51 const std::string& pub_topic,
52 const ros::NodeHandle &nh,
53 const unsigned int queue_size = 10);
55 geometry_msgs::Pose& pose);
56 void CopyVec3D(
const rapid::Vec3d& vec_in, geometry_msgs::Vector3& vec_out);
61 void operator() (rapid::ext::astrobee::EkfState
const* ekf_sample);
64 std::string subscriber_partition_;
69 #endif // DDS_ROS_BRIDGE_RAPID_EKF_ROS_EKF_H_
void CopyTransform3D(const rapid::Transform3D &transform, geometry_msgs::Pose &pose)
Definition: rapid_ekf_ros_ekf.cc:58
RapidEkfToRos(const std::string &subscribe_topic, const std::string &subscribe_partition, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size=10)
Definition: rapid_ekf_ros_ekf.cc:23
void operator()(rapid::ext::astrobee::EkfState const *ekf_sample)
Definition: rapid_ekf_ros_ekf.cc:77
Definition: generic_rapid_msg_ros_pub.h:36
base class for rapid subscriber to ros publisher
Definition: rapid_sub_ros_pub.h:42
void CopyVec3D(const rapid::Vec3d &vec_in, geometry_msgs::Vector3 &vec_out)
Definition: rapid_ekf_ros_ekf.cc:70
Definition: rapid_ekf_ros_ekf.h:47