#include <hebiros_gazebo_group.h>
Public Member Functions | |
HebirosGazeboGroup (std::string name, std::shared_ptr< ros::NodeHandle > n) | |
bool | SrvAcknowledge (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
bool | SrvSetCommandLifetime (SetCommandLifetimeSrv::Request &req, SetCommandLifetimeSrv::Response &res) |
bool | SrvSetFeedbackFrequency (SetFeedbackFrequencySrv::Request &req, SetFeedbackFrequencySrv::Response &res) |
void | SubCommand (const boost::shared_ptr< CommandMsg const > data) |
Public Attributes | |
ros::ServiceServer | acknowledge_srv |
bool | acknowledgement = false |
bool | check_acknowledgement = false |
int | command_lifetime = 100 |
ros::ServiceServer | command_lifetime_srv |
bool | command_received = false |
ros::Subscriber | command_sub |
CommandMsg | command_target |
FeedbackMsg | feedback |
int | feedback_frequency = 100 |
ros::ServiceServer | feedback_frequency_srv |
ros::Publisher | feedback_pub |
bool | group_added = false |
std::map< std::string, std::shared_ptr< HebirosGazeboJoint > > | joints |
std::string | name |
ros::Time | prev_feedback_time |
ros::Time | prev_time |
SettingsMsg | settings |
ros::Time | start_time |
Definition at line 14 of file hebiros_gazebo_group.h.
HebirosGazeboGroup::HebirosGazeboGroup | ( | std::string | name, |
std::shared_ptr< ros::NodeHandle > | n | ||
) |
Definition at line 4 of file hebiros_gazebo_group.cpp.
bool HebirosGazeboGroup::SrvAcknowledge | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | res | ||
) |
Definition at line 63 of file hebiros_gazebo_group.cpp.
bool HebirosGazeboGroup::SrvSetCommandLifetime | ( | SetCommandLifetimeSrv::Request & | req, |
SetCommandLifetimeSrv::Response & | res | ||
) |
Definition at line 78 of file hebiros_gazebo_group.cpp.
bool HebirosGazeboGroup::SrvSetFeedbackFrequency | ( | SetFeedbackFrequencySrv::Request & | req, |
SetFeedbackFrequencySrv::Response & | res | ||
) |
Definition at line 85 of file hebiros_gazebo_group.cpp.
void HebirosGazeboGroup::SubCommand | ( | const boost::shared_ptr< CommandMsg const > | data | ) |
Definition at line 32 of file hebiros_gazebo_group.cpp.
ros::ServiceServer HebirosGazeboGroup::acknowledge_srv |
Definition at line 37 of file hebiros_gazebo_group.h.
bool HebirosGazeboGroup::acknowledgement = false |
Definition at line 25 of file hebiros_gazebo_group.h.
bool HebirosGazeboGroup::check_acknowledgement = false |
Definition at line 24 of file hebiros_gazebo_group.h.
int HebirosGazeboGroup::command_lifetime = 100 |
Definition at line 28 of file hebiros_gazebo_group.h.
ros::ServiceServer HebirosGazeboGroup::command_lifetime_srv |
Definition at line 38 of file hebiros_gazebo_group.h.
bool HebirosGazeboGroup::command_received = false |
Definition at line 26 of file hebiros_gazebo_group.h.
ros::Subscriber HebirosGazeboGroup::command_sub |
Definition at line 35 of file hebiros_gazebo_group.h.
CommandMsg HebirosGazeboGroup::command_target |
Definition at line 22 of file hebiros_gazebo_group.h.
FeedbackMsg HebirosGazeboGroup::feedback |
Definition at line 21 of file hebiros_gazebo_group.h.
int HebirosGazeboGroup::feedback_frequency = 100 |
Definition at line 29 of file hebiros_gazebo_group.h.
ros::ServiceServer HebirosGazeboGroup::feedback_frequency_srv |
Definition at line 39 of file hebiros_gazebo_group.h.
ros::Publisher HebirosGazeboGroup::feedback_pub |
Definition at line 36 of file hebiros_gazebo_group.h.
bool HebirosGazeboGroup::group_added = false |
Definition at line 27 of file hebiros_gazebo_group.h.
std::map<std::string, std::shared_ptr<HebirosGazeboJoint> > HebirosGazeboGroup::joints |
Definition at line 20 of file hebiros_gazebo_group.h.
std::string HebirosGazeboGroup::name |
Definition at line 19 of file hebiros_gazebo_group.h.
ros::Time HebirosGazeboGroup::prev_feedback_time |
Definition at line 33 of file hebiros_gazebo_group.h.
ros::Time HebirosGazeboGroup::prev_time |
Definition at line 32 of file hebiros_gazebo_group.h.
SettingsMsg HebirosGazeboGroup::settings |
Definition at line 23 of file hebiros_gazebo_group.h.
ros::Time HebirosGazeboGroup::start_time |
Definition at line 31 of file hebiros_gazebo_group.h.