#include <ros_battery_state.h>
|
| RosBatteryStateToRapid (std::string const &sub_topic_battery_state_TL, std::string const &sub_topic_battery_state_TR, std::string const &sub_topic_battery_state_BL, std::string const &sub_topic_battery_state_BR, std::string const &sub_topic_battery_temp_TL, std::string const &sub_topic_battery_temp_TR, std::string const &sub_topic_battery_temp_BL, std::string const &sub_topic_battery_temp_BR, std::string const &pub_topic, ros::NodeHandle const &nh, const unsigned int queue_size=10) |
|
void | AddTempToState (rapid::ext::astrobee::BatterySlot slot, float temp) |
|
rapid::ext::astrobee::BatterySlot | ConvertBatteryLoc (std::string const &slot) |
|
void | SetBatteryTimeMultiple (int multiple) |
|
void | StateCallback (sensor_msgs::BatteryStateConstPtr const &state) |
|
void | TempTLCallback (sensor_msgs::TemperatureConstPtr const &temp) |
|
void | TempTRCallback (sensor_msgs::TemperatureConstPtr const &temp) |
|
void | TempBLCallback (sensor_msgs::TemperatureConstPtr const &temp) |
|
void | TempBRCallback (sensor_msgs::TemperatureConstPtr const &temp) |
|
|
| 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_ |
|
◆ RosBatteryStateToRapid()
ff::RosBatteryStateToRapid::RosBatteryStateToRapid |
( |
std::string const & |
sub_topic_battery_state_TL, |
|
|
std::string const & |
sub_topic_battery_state_TR, |
|
|
std::string const & |
sub_topic_battery_state_BL, |
|
|
std::string const & |
sub_topic_battery_state_BR, |
|
|
std::string const & |
sub_topic_battery_temp_TL, |
|
|
std::string const & |
sub_topic_battery_temp_TR, |
|
|
std::string const & |
sub_topic_battery_temp_BL, |
|
|
std::string const & |
sub_topic_battery_temp_BR, |
|
|
std::string const & |
pub_topic, |
|
|
ros::NodeHandle const & |
nh, |
|
|
const unsigned int |
queue_size = 10 |
|
) |
| |
◆ AddTempToState()
void ff::RosBatteryStateToRapid::AddTempToState |
( |
rapid::ext::astrobee::BatterySlot |
slot, |
|
|
float |
temp |
|
) |
| |
◆ ConvertBatteryLoc()
rapid::ext::astrobee::BatterySlot ff::RosBatteryStateToRapid::ConvertBatteryLoc |
( |
std::string const & |
slot | ) |
|
◆ SetBatteryTimeMultiple()
void ff::RosBatteryStateToRapid::SetBatteryTimeMultiple |
( |
int |
multiple | ) |
|
◆ StateCallback()
void ff::RosBatteryStateToRapid::StateCallback |
( |
sensor_msgs::BatteryStateConstPtr const & |
state | ) |
|
◆ TempBLCallback()
void ff::RosBatteryStateToRapid::TempBLCallback |
( |
sensor_msgs::TemperatureConstPtr const & |
temp | ) |
|
◆ TempBRCallback()
void ff::RosBatteryStateToRapid::TempBRCallback |
( |
sensor_msgs::TemperatureConstPtr const & |
temp | ) |
|
◆ TempTLCallback()
void ff::RosBatteryStateToRapid::TempTLCallback |
( |
sensor_msgs::TemperatureConstPtr const & |
temp | ) |
|
◆ TempTRCallback()
void ff::RosBatteryStateToRapid::TempTRCallback |
( |
sensor_msgs::TemperatureConstPtr const & |
temp | ) |
|
The documentation for this class was generated from the following files: