#include <rapid_gs_data_ros_gs_data.h>
|
| RapidGuestScienceDataToRos (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 | operator() (rapid::ext::astrobee::GuestScienceData const *data) |
|
| RapidGuestScienceDataToRos (const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size=10) |
|
void | operator() (rapid::ext::astrobee::GuestScienceData const *rapid_gs_data) |
|
◆ RapidGuestScienceDataToRos() [1/2]
ff::RapidGuestScienceDataToRos::RapidGuestScienceDataToRos |
( |
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 |
|
) |
| |
◆ RapidGuestScienceDataToRos() [2/2]
ff::RapidGuestScienceDataToRos::RapidGuestScienceDataToRos |
( |
const std::string & |
subscribe_topic, |
|
|
const std::string & |
pub_topic, |
|
|
const ros::NodeHandle & |
nh, |
|
|
const unsigned int |
queue_size = 10 |
|
) |
| |
◆ operator()() [1/2]
void ff::RapidGuestScienceDataToRos::operator() |
( |
rapid::ext::astrobee::GuestScienceData const * |
data | ) |
|
call back for ddsEventLoop
◆ operator()() [2/2]
void ff::RapidGuestScienceDataToRos::operator() |
( |
rapid::ext::astrobee::GuestScienceData const * |
rapid_gs_data | ) |
|
The documentation for this class was generated from the following files: