#include <common_state_callbacks.h>
Public Member Functions | |
CommonCommonStateProductModel (::ros::NodeHandle &nh,::ros::NodeHandle &priv_nh, const ::std::string &topic) | |
::bebop_msgs::CommonCommonStateProductModel::ConstPtr | GetDataCstPtr () const |
void | Update (const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time &t) |
Private Attributes | |
::bebop_msgs::CommonCommonStateProductModel::Ptr | msg_ptr |
Definition at line 607 of file common_state_callbacks.h.
bebop_driver::cb::CommonCommonStateProductModel::CommonCommonStateProductModel | ( | ::ros::NodeHandle & | nh, |
::ros::NodeHandle & | priv_nh, | ||
const ::std::string & | topic | ||
) | [inline] |
Definition at line 614 of file common_state_callbacks.h.
::bebop_msgs::CommonCommonStateProductModel::ConstPtr bebop_driver::cb::CommonCommonStateProductModel::GetDataCstPtr | ( | ) | const [inline] |
Definition at line 624 of file common_state_callbacks.h.
void bebop_driver::cb::CommonCommonStateProductModel::Update | ( | const ARCONTROLLER_DICTIONARY_ARG_t * | arguments, |
const ::ros::Time & | t | ||
) | [inline, virtual] |
Implements bebop_driver::cb::AbstractCommand.
Definition at line 630 of file common_state_callbacks.h.
::bebop_msgs::CommonCommonStateProductModel::Ptr bebop_driver::cb::CommonCommonStateProductModel::msg_ptr [private] |
Definition at line 610 of file common_state_callbacks.h.