#include <gazebo_ros_actuator_array.h>
Public Member Functions | |
GazeboRosActuatorArray (Entity *parent) | |
Constructor. | |
virtual | ~GazeboRosActuatorArray () |
Protected Member Functions | |
virtual void | FiniChild () |
virtual void | InitChild () |
virtual void | LoadChild (XMLConfigNode *node) |
virtual void | UpdateChild () |
Private Member Functions | |
bool | command_ () |
pure virtual function that handles sensing a command to the device. This gets called once after every message received on the 'command' topic. The internal command_msg_ will already be updated with the new command information | |
bool | home_ () |
pure virtual function that sends the device to the home position. This gets called in response to a 'home' service call | |
void | parse_mimic_joints (const ros::NodeHandle &node) |
void | QueueThread () |
bool | read_ (ros::Time ts=ros::Time::now()) |
pure virtual function that is responsible for reading the current deivce state and updating the internal joint_state_msg_ | |
bool | stop_ () |
pure virtual function that sends a stop command to the device. This gets called in response to a 'stop' service call | |
void | update_joint (GazeboJointProperties &gazebo_joint, double command_position, double command_velocity, double command_effort, double dt) |
Private Attributes | |
boost::thread | callback_queue_thread_ |
gazebo::Time | last_time_ |
Time of previous update. | |
boost::mutex | lock_ |
A mutex to lock access to fields that are used in message callbacks. | |
std::map< std::string, MimicJointProperties > | mimic_joints_ |
A second set of joint properties for handling Gazebo Mimic joints. | |
Model * | myParent |
The parent Model. | |
ros::CallbackQueue | queue_ |
std::string | robot_namespace_ |
ParamT< std::string > * | robotNamespaceP |
for setting ROS name space | |
ParamT< std::string > * | robotParamP |
for setting the parameter name that holds the robot description |
Definition at line 192 of file gazebo_ros_actuator_array.h.
gazebo::GazeboRosActuatorArray::GazeboRosActuatorArray | ( | Entity * | parent | ) |
Constructor.
Definition at line 55 of file gazebo_ros_actuator_array.cpp.
gazebo::GazeboRosActuatorArray::~GazeboRosActuatorArray | ( | ) | [virtual] |
Definition at line 71 of file gazebo_ros_actuator_array.cpp.
bool gazebo::GazeboRosActuatorArray::command_ | ( | ) | [private, virtual] |
pure virtual function that handles sensing a command to the device. This gets called once after every message received on the 'command' topic. The internal command_msg_ will already be updated with the new command information
Reimplemented from actuator_array_driver::ActuatorArrayDriver< GazeboJointProperties >.
Definition at line 452 of file gazebo_ros_actuator_array.cpp.
void gazebo::GazeboRosActuatorArray::FiniChild | ( | ) | [protected, virtual] |
Definition at line 276 of file gazebo_ros_actuator_array.cpp.
bool gazebo::GazeboRosActuatorArray::home_ | ( | ) | [private, virtual] |
pure virtual function that sends the device to the home position. This gets called in response to a 'home' service call
Reimplemented from actuator_array_driver::ActuatorArrayDriver< GazeboJointProperties >.
Definition at line 476 of file gazebo_ros_actuator_array.cpp.
void gazebo::GazeboRosActuatorArray::InitChild | ( | ) | [protected, virtual] |
Definition at line 202 of file gazebo_ros_actuator_array.cpp.
void gazebo::GazeboRosActuatorArray::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Definition at line 79 of file gazebo_ros_actuator_array.cpp.
void gazebo::GazeboRosActuatorArray::parse_mimic_joints | ( | const ros::NodeHandle & | node | ) | [private] |
Definition at line 380 of file gazebo_ros_actuator_array.cpp.
void gazebo::GazeboRosActuatorArray::QueueThread | ( | ) | [private] |
bool gazebo::GazeboRosActuatorArray::read_ | ( | ros::Time | ts = ros::Time::now() | ) | [private, virtual] |
pure virtual function that is responsible for reading the current deivce state and updating the internal joint_state_msg_
Reimplemented from actuator_array_driver::ActuatorArrayDriver< GazeboJointProperties >.
Definition at line 492 of file gazebo_ros_actuator_array.cpp.
bool gazebo::GazeboRosActuatorArray::stop_ | ( | ) | [private, virtual] |
pure virtual function that sends a stop command to the device. This gets called in response to a 'stop' service call
Reimplemented from actuator_array_driver::ActuatorArrayDriver< GazeboJointProperties >.
Definition at line 460 of file gazebo_ros_actuator_array.cpp.
void gazebo::GazeboRosActuatorArray::update_joint | ( | GazeboJointProperties & | gazebo_joint, |
double | command_position, | ||
double | command_velocity, | ||
double | command_effort, | ||
double | dt | ||
) | [private] |
Definition at line 302 of file gazebo_ros_actuator_array.cpp.
void gazebo::GazeboRosActuatorArray::UpdateChild | ( | ) | [protected, virtual] |
Definition at line 215 of file gazebo_ros_actuator_array.cpp.
boost::thread gazebo::GazeboRosActuatorArray::callback_queue_thread_ [private] |
Definition at line 229 of file gazebo_ros_actuator_array.h.
gazebo::Time gazebo::GazeboRosActuatorArray::last_time_ [private] |
Time of previous update.
Definition at line 221 of file gazebo_ros_actuator_array.h.
boost::mutex gazebo::GazeboRosActuatorArray::lock_ [private] |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 224 of file gazebo_ros_actuator_array.h.
std::map<std::string, MimicJointProperties> gazebo::GazeboRosActuatorArray::mimic_joints_ [private] |
A second set of joint properties for handling Gazebo Mimic joints.
Definition at line 215 of file gazebo_ros_actuator_array.h.
Model* gazebo::GazeboRosActuatorArray::myParent [private] |
The parent Model.
Definition at line 218 of file gazebo_ros_actuator_array.h.
Definition at line 227 of file gazebo_ros_actuator_array.h.
std::string gazebo::GazeboRosActuatorArray::robot_namespace_ [private] |
Definition at line 209 of file gazebo_ros_actuator_array.h.
ParamT<std::string>* gazebo::GazeboRosActuatorArray::robotNamespaceP [private] |
for setting ROS name space
Definition at line 208 of file gazebo_ros_actuator_array.h.
ParamT<std::string>* gazebo::GazeboRosActuatorArray::robotParamP [private] |
for setting the parameter name that holds the robot description
Definition at line 212 of file gazebo_ros_actuator_array.h.