NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
ff::RosEkfToRapid Class Reference

#include <ros_ekf_rapid_ekf.h>

Inheritance diagram for ff::RosEkfToRapid:
Inheritance graph

Public Member Functions

 RosEkfToRapid (const std::string &subscribe_topic, const std::string &pub_topic, const std::string &rapid_pub_name, const ros::NodeHandle &nh, const unsigned int queue_size=10)
 
void CopyTransform3D (rapid::Transform3D &transform, const geometry_msgs::Pose &pose)
 
void CopyVec3D (rapid::Vec3d &vec_out, const geometry_msgs::Vector3 &vec_in)
 
void MsgCallback (const ff_msgs::EkfStateConstPtr &msg)
 
void PubEkf (const ros::TimerEvent &event)
 
void SetEkfPublishRate (float rate)
 

Additional Inherited Members

- Protected Member Functions inherited from ff::RosSubRapidPub
 RosSubRapidPub (const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size)
 
 RosSubRapidPub (const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size)
 
- Protected Attributes inherited from ff::RosSubRapidPub
ros::NodeHandle nh_
 
ros::Subscriber sub_
 
std::string subscribe_topic_
 
std::string publish_topic_
 
unsigned int queue_size_
 

Constructor & Destructor Documentation

◆ RosEkfToRapid()

ff::RosEkfToRapid::RosEkfToRapid ( const std::string &  subscribe_topic,
const std::string &  pub_topic,
const std::string &  rapid_pub_name,
const ros::NodeHandle &  nh,
const unsigned int  queue_size = 10 
)

Member Function Documentation

◆ CopyTransform3D()

void ff::RosEkfToRapid::CopyTransform3D ( rapid::Transform3D &  transform,
const geometry_msgs::Pose &  pose 
)

◆ CopyVec3D()

void ff::RosEkfToRapid::CopyVec3D ( rapid::Vec3d &  vec_out,
const geometry_msgs::Vector3 &  vec_in 
)

◆ MsgCallback()

void ff::RosEkfToRapid::MsgCallback ( const ff_msgs::EkfStateConstPtr &  msg)

◆ PubEkf()

void ff::RosEkfToRapid::PubEkf ( const ros::TimerEvent &  event)

◆ SetEkfPublishRate()

void ff::RosEkfToRapid::SetEkfPublishRate ( float  rate)

The documentation for this class was generated from the following files: