#include <hebiros_gazebo_plugin.h>
Public Member Functions | |
HebirosGazeboPlugin ()=default | |
void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
void | OnUpdate (const common::UpdateInfo &_info) |
Private Member Functions | |
void | AddJointToGroup (std::shared_ptr< HebirosGazeboGroup > hebiros_group, std::string joint_name) |
bool | SrvAddGroup (AddGroupFromNamesSrv::Request &req, AddGroupFromNamesSrv::Response &res) |
void | UpdateGroup (std::shared_ptr< HebirosGazeboGroup > hebiros_group, const ros::Duration &iteration_time) |
Private Attributes | |
ros::ServiceServer | acknowledge_srv |
ros::ServiceServer | add_group_srv |
ros::Subscriber | command_sub |
std::map< std::string, std::shared_ptr< HebirosGazeboGroup > > | hebiros_groups |
std::map< std::string, std::shared_ptr< HebirosGazeboJoint > > | hebiros_joints |
physics::ModelPtr | model |
std::shared_ptr< ros::NodeHandle > | n |
std::string | robot_namespace |
event::ConnectionPtr | update_connection |
Definition at line 26 of file hebiros_gazebo_plugin.h.
|
default |
|
private |
Definition at line 172 of file hebiros_gazebo_plugin.cpp.
void HebirosGazeboPlugin::Load | ( | physics::ModelPtr | _model, |
sdf::ElementPtr | _sdf | ||
) |
Definition at line 4 of file hebiros_gazebo_plugin.cpp.
void HebirosGazeboPlugin::OnUpdate | ( | const common::UpdateInfo & | _info | ) |
Definition at line 33 of file hebiros_gazebo_plugin.cpp.
|
private |
Definition at line 122 of file hebiros_gazebo_plugin.cpp.
|
private |
Definition at line 49 of file hebiros_gazebo_plugin.cpp.
|
private |
Definition at line 45 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 44 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 43 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 38 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 39 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 36 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 42 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 41 of file hebiros_gazebo_plugin.h.
|
private |
Definition at line 37 of file hebiros_gazebo_plugin.h.