#include <ros_pmc_cmd_state.h>
|
| RosPmcCmdStateToRapid (const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size=10) |
|
void | CopyPmcGoal (const ff_hw_msgs::PmcGoal &ros_goal, rapid::ext::astrobee::PmcGoal &dds_goal) |
|
void | MsgCallback (const ff_hw_msgs::PmcCommandConstPtr &msg) |
|
void | PubPmcCmdState (const ros::TimerEvent &event) |
|
void | SetPmcPublishRate (float rate) |
|
|
| 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) |
|
ros::NodeHandle | nh_ |
|
ros::Subscriber | sub_ |
|
std::string | subscribe_topic_ |
|
std::string | publish_topic_ |
|
unsigned int | queue_size_ |
|
◆ RosPmcCmdStateToRapid()
ff::RosPmcCmdStateToRapid::RosPmcCmdStateToRapid |
( |
const std::string & |
subscribe_topic, |
|
|
const std::string & |
pub_topic, |
|
|
const ros::NodeHandle & |
nh, |
|
|
const unsigned int |
queue_size = 10 |
|
) |
| |
◆ CopyPmcGoal()
void ff::RosPmcCmdStateToRapid::CopyPmcGoal |
( |
const ff_hw_msgs::PmcGoal & |
ros_goal, |
|
|
rapid::ext::astrobee::PmcGoal & |
dds_goal |
|
) |
| |
◆ MsgCallback()
void ff::RosPmcCmdStateToRapid::MsgCallback |
( |
const ff_hw_msgs::PmcCommandConstPtr & |
msg | ) |
|
◆ PubPmcCmdState()
void ff::RosPmcCmdStateToRapid::PubPmcCmdState |
( |
const ros::TimerEvent & |
event | ) |
|
◆ SetPmcPublishRate()
void ff::RosPmcCmdStateToRapid::SetPmcPublishRate |
( |
float |
rate | ) |
|
The documentation for this class was generated from the following files: