Public Member Functions | Private Member Functions | Private Attributes | List of all members
HebirosGazeboPlugin Class Reference

#include <hebiros_gazebo_plugin.h>

Inheritance diagram for HebirosGazeboPlugin:
Inheritance graph
[legend]

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::NodeHandlen
 
std::string robot_namespace
 
event::ConnectionPtr update_connection
 

Detailed Description

Definition at line 26 of file hebiros_gazebo_plugin.h.

Constructor & Destructor Documentation

HebirosGazeboPlugin::HebirosGazeboPlugin ( )
default

Member Function Documentation

void HebirosGazeboPlugin::AddJointToGroup ( std::shared_ptr< HebirosGazeboGroup hebiros_group,
std::string  joint_name 
)
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.

bool HebirosGazeboPlugin::SrvAddGroup ( AddGroupFromNamesSrv::Request &  req,
AddGroupFromNamesSrv::Response &  res 
)
private

Definition at line 122 of file hebiros_gazebo_plugin.cpp.

void HebirosGazeboPlugin::UpdateGroup ( std::shared_ptr< HebirosGazeboGroup hebiros_group,
const ros::Duration iteration_time 
)
private

Definition at line 49 of file hebiros_gazebo_plugin.cpp.

Member Data Documentation

ros::ServiceServer HebirosGazeboPlugin::acknowledge_srv
private

Definition at line 45 of file hebiros_gazebo_plugin.h.

ros::ServiceServer HebirosGazeboPlugin::add_group_srv
private

Definition at line 44 of file hebiros_gazebo_plugin.h.

ros::Subscriber HebirosGazeboPlugin::command_sub
private

Definition at line 43 of file hebiros_gazebo_plugin.h.

std::map<std::string, std::shared_ptr<HebirosGazeboGroup> > HebirosGazeboPlugin::hebiros_groups
private

Definition at line 38 of file hebiros_gazebo_plugin.h.

std::map<std::string, std::shared_ptr<HebirosGazeboJoint> > HebirosGazeboPlugin::hebiros_joints
private

Definition at line 39 of file hebiros_gazebo_plugin.h.

physics::ModelPtr HebirosGazeboPlugin::model
private

Definition at line 36 of file hebiros_gazebo_plugin.h.

std::shared_ptr<ros::NodeHandle> HebirosGazeboPlugin::n
private

Definition at line 42 of file hebiros_gazebo_plugin.h.

std::string HebirosGazeboPlugin::robot_namespace
private

Definition at line 41 of file hebiros_gazebo_plugin.h.

event::ConnectionPtr HebirosGazeboPlugin::update_connection
private

Definition at line 37 of file hebiros_gazebo_plugin.h.


The documentation for this class was generated from the following files:


hebiros_gazebo_plugin
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:13:55