#include <gazebo_ros_controller_manager.h>
Public Member Functions | |
GazeboRosControllerManager (Entity *parent) | |
virtual | ~GazeboRosControllerManager () |
Protected Member Functions | |
virtual void | FiniChild () |
virtual void | InitChild () |
virtual void | LoadChild (XMLConfigNode *node) |
virtual void | UpdateChild () |
Private Member Functions | |
void | ControllerManagerROSThread () |
void | ReadPr2Xml (XMLConfigNode *node) |
bool | setModelsJointsStates (pr2_gazebo_plugins::SetModelsJointsStates::Request &req, pr2_gazebo_plugins::SetModelsJointsStates::Response &res) |
ros service callback | |
Private Attributes | |
pr2_controller_manager::ControllerManager * | cm_ |
bool | fake_calibration_ |
pr2_mechanism_model::RobotState * | fake_state_ |
pr2_hardware_interface::HardwareInterface | hw_ |
std::vector< gazebo::Joint * > | joints_ |
Model * | parent_model_ |
std::string | robotNamespace |
ParamT< std::string > * | robotNamespaceP |
std::string | robotParam |
ParamT< std::string > * | robotParamP |
set topic name of robot description parameter | |
boost::thread | ros_spinner_thread_ |
ros::NodeHandle * | rosnode_ |
ros::ServiceServer | setModelsJointsStatesService |
ros service | |
std::string | setModelsJointsStatesServiceName |
ParamT< std::string > * | setModelsJointsStatesServiceNameP |
Service Call Name. | |
double | sim_start_ |
double | wall_start_ |
ros service callback |
This is a controller plugin that provides interface between simulated robot and pr2_controller_manager. controller:gazebo_ros_controller_manager XML extension requires a model as its parent. Please see pr2_description for example usages in the pr2_simulator.
Gazebo simulator provides joint force/torque control for simulated joints and links. This plugin exposes a set of pseudo-actuator states to pr2_controller_manager through ros by the use of inverse transmissions as defined in pr2_mechanism_controllers.
<!-- GazeboRosControllerMangager --> <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so"> <alwaysOn>true</alwaysOn> <updateRate>1000.0</updateRate> <robotParam>robot_description</robotParam> <robotNamespace>/</robotNamespace> </controller:gazebo_ros_controller_manager>
Definition at line 95 of file gazebo_ros_controller_manager.h.
gazebo::GazeboRosControllerManager::GazeboRosControllerManager | ( | Entity * | parent | ) |
Definition at line 56 of file gazebo_ros_controller_manager.cpp.
gazebo::GazeboRosControllerManager::~GazeboRosControllerManager | ( | ) | [virtual] |
Definition at line 99 of file gazebo_ros_controller_manager.cpp.
void gazebo::GazeboRosControllerManager::ControllerManagerROSThread | ( | ) | [private] |
Definition at line 488 of file gazebo_ros_controller_manager.cpp.
void gazebo::GazeboRosControllerManager::FiniChild | ( | ) | [protected, virtual] |
Definition at line 385 of file gazebo_ros_controller_manager.cpp.
void gazebo::GazeboRosControllerManager::InitChild | ( | ) | [protected, virtual] |
Definition at line 171 of file gazebo_ros_controller_manager.cpp.
void gazebo::GazeboRosControllerManager::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Definition at line 114 of file gazebo_ros_controller_manager.cpp.
void gazebo::GazeboRosControllerManager::ReadPr2Xml | ( | XMLConfigNode * | node | ) | [private] |
Definition at line 402 of file gazebo_ros_controller_manager.cpp.
bool gazebo::GazeboRosControllerManager::setModelsJointsStates | ( | pr2_gazebo_plugins::SetModelsJointsStates::Request & | req, | |
pr2_gazebo_plugins::SetModelsJointsStates::Response & | res | |||
) | [private] |
ros service callback
void gazebo::GazeboRosControllerManager::UpdateChild | ( | ) | [protected, virtual] |
FIXME: if damping is greater than this value, do some unconventional smoothing to prevent instability due to safety controller
Definition at line 188 of file gazebo_ros_controller_manager.cpp.
pr2_controller_manager::ControllerManager* gazebo::GazeboRosControllerManager::cm_ [private] |
Definition at line 112 of file gazebo_ros_controller_manager.h.
bool gazebo::GazeboRosControllerManager::fake_calibration_ [private] |
Definition at line 153 of file gazebo_ros_controller_manager.h.
pr2_mechanism_model::RobotState* gazebo::GazeboRosControllerManager::fake_state_ [private] |
Definition at line 117 of file gazebo_ros_controller_manager.h.
pr2_hardware_interface::HardwareInterface gazebo::GazeboRosControllerManager::hw_ [private] |
Definition at line 111 of file gazebo_ros_controller_manager.h.
std::vector<gazebo::Joint*> gazebo::GazeboRosControllerManager::joints_ [private] |
Definition at line 118 of file gazebo_ros_controller_manager.h.
Model* gazebo::GazeboRosControllerManager::parent_model_ [private] |
Definition at line 110 of file gazebo_ros_controller_manager.h.
std::string gazebo::GazeboRosControllerManager::robotNamespace [private] |
Definition at line 151 of file gazebo_ros_controller_manager.h.
ParamT<std::string>* gazebo::GazeboRosControllerManager::robotNamespaceP [private] |
Definition at line 149 of file gazebo_ros_controller_manager.h.
std::string gazebo::GazeboRosControllerManager::robotParam [private] |
Definition at line 150 of file gazebo_ros_controller_manager.h.
ParamT<std::string>* gazebo::GazeboRosControllerManager::robotParamP [private] |
set topic name of robot description parameter
Definition at line 148 of file gazebo_ros_controller_manager.h.
boost::thread gazebo::GazeboRosControllerManager::ros_spinner_thread_ [private] |
Definition at line 161 of file gazebo_ros_controller_manager.h.
ros::NodeHandle* gazebo::GazeboRosControllerManager::rosnode_ [private] |
Definition at line 132 of file gazebo_ros_controller_manager.h.
ros::ServiceServer gazebo::GazeboRosControllerManager::setModelsJointsStatesService [private] |
ros service
Definition at line 135 of file gazebo_ros_controller_manager.h.
std::string gazebo::GazeboRosControllerManager::setModelsJointsStatesServiceName [private] |
Definition at line 122 of file gazebo_ros_controller_manager.h.
ParamT<std::string>* gazebo::GazeboRosControllerManager::setModelsJointsStatesServiceNameP [private] |
Service Call Name.
Definition at line 121 of file gazebo_ros_controller_manager.h.
double gazebo::GazeboRosControllerManager::sim_start_ [private] |
Definition at line 145 of file gazebo_ros_controller_manager.h.
double gazebo::GazeboRosControllerManager::wall_start_ [private] |
ros service callback
Definition at line 145 of file gazebo_ros_controller_manager.h.