#include <rapid_ekf_ros_ekf.h>
|
| 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) |
|
void | CopyTransform3D (const rapid::Transform3D &transform, geometry_msgs::Pose &pose) |
|
void | CopyVec3D (const rapid::Vec3d &vec_in, geometry_msgs::Vector3 &vec_out) |
|
void | operator() (rapid::ext::astrobee::EkfState const *ekf_sample) |
|
◆ RapidEkfToRos()
ff::RapidEkfToRos::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 |
|
) |
| |
◆ CopyTransform3D()
void ff::RapidEkfToRos::CopyTransform3D |
( |
const rapid::Transform3D & |
transform, |
|
|
geometry_msgs::Pose & |
pose |
|
) |
| |
◆ CopyVec3D()
void ff::RapidEkfToRos::CopyVec3D |
( |
const rapid::Vec3d & |
vec_in, |
|
|
geometry_msgs::Vector3 & |
vec_out |
|
) |
| |
◆ operator()()
void ff::RapidEkfToRos::operator() |
( |
rapid::ext::astrobee::EkfState const * |
ekf_sample | ) |
|
call back for ddsEventLoop
The documentation for this class was generated from the following files: