Public Member Functions
gazebo_ros_control::RobotHWSim Class Reference

Gazebo plugin version of RobotHW. More...

#include <robot_hw_sim.h>

Inheritance diagram for gazebo_ros_control::RobotHWSim:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void eStopActive (const bool active)
 Set the emergency stop state.
virtual bool initSim (const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *const urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions)=0
 Initialize the simulated robot hardware.
virtual void readSim (ros::Time time, ros::Duration period)=0
 Read state data from the simulated robot hardware.
virtual void writeSim (ros::Time time, ros::Duration period)=0
 Write commands to the simulated robot hardware.
virtual ~RobotHWSim ()

Detailed Description

Gazebo plugin version of RobotHW.

An object of class RobotHWSim represents a robot's simulated hardware.

Definition at line 68 of file robot_hw_sim.h.


Constructor & Destructor Documentation

virtual gazebo_ros_control::RobotHWSim::~RobotHWSim ( ) [inline, virtual]

Definition at line 72 of file robot_hw_sim.h.


Member Function Documentation

virtual void gazebo_ros_control::RobotHWSim::eStopActive ( const bool  active) [inline, virtual]

Set the emergency stop state.

Set the simulated robot's emergency stop state. The default implementation of this function does nothing.

Parameters:
activetrue if the emergency stop is active, false if not.

Reimplemented in gazebo_ros_control::DefaultRobotHWSim.

Definition at line 113 of file robot_hw_sim.h.

virtual bool gazebo_ros_control::RobotHWSim::initSim ( const std::string &  robot_namespace,
ros::NodeHandle  model_nh,
gazebo::physics::ModelPtr  parent_model,
const urdf::Model *const  urdf_model,
std::vector< transmission_interface::TransmissionInfo transmissions 
) [pure virtual]

Initialize the simulated robot hardware.

Initialize the simulated robot hardware.

Parameters:
robot_namespaceRobot namespace.
model_nhModel node handle.
parent_modelParent model.
urdf_modelURDF model.
transmissionsTransmissions.
Returns:
true if the simulated robot hardware is initialized successfully, false if not.

Implemented in gazebo_ros_control::DefaultRobotHWSim.

virtual void gazebo_ros_control::RobotHWSim::readSim ( ros::Time  time,
ros::Duration  period 
) [pure virtual]

Read state data from the simulated robot hardware.

Read state data, such as joint positions and velocities, from the simulated robot hardware.

Parameters:
timeSimulation time.
periodTime since the last simulation step.

Implemented in gazebo_ros_control::DefaultRobotHWSim.

virtual void gazebo_ros_control::RobotHWSim::writeSim ( ros::Time  time,
ros::Duration  period 
) [pure virtual]

Write commands to the simulated robot hardware.

Write commands, such as joint position and velocity commands, to the simulated robot hardware.

Parameters:
timeSimulation time.
periodTime since the last simulation step.

Implemented in gazebo_ros_control::DefaultRobotHWSim.


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


gazebo_ros_control
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Thu Feb 23 2017 03:43:51