#include <default_robot_hw_sim.h>
Definition at line 74 of file default_robot_hw_sim.h.
enum gazebo_ros_control::DefaultRobotHWSim::ControlMethod [protected] |
Definition at line 93 of file default_robot_hw_sim.h.
void gazebo_ros_control::DefaultRobotHWSim::eStopActive | ( | const bool | active | ) | [virtual] |
Set the emergency stop state.
Set the simulated robot's emergency stop state. The default implementation of this function does nothing.
active | true if the emergency stop is active, false if not. |
Reimplemented from gazebo_ros_control::RobotHWSim.
Definition at line 356 of file default_robot_hw_sim.cpp.
bool gazebo_ros_control::DefaultRobotHWSim::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 | ||
) | [virtual] |
Initialize the simulated robot hardware.
Initialize the simulated robot hardware.
robot_namespace | Robot namespace. |
model_nh | Model node handle. |
parent_model | Parent model. |
urdf_model | URDF model. |
transmissions | Transmissions. |
true
if the simulated robot hardware is initialized successfully, false
if not. Implements gazebo_ros_control::RobotHWSim.
Definition at line 59 of file default_robot_hw_sim.cpp.
void gazebo_ros_control::DefaultRobotHWSim::readSim | ( | ros::Time | time, |
ros::Duration | period | ||
) | [virtual] |
Read state data from the simulated robot hardware.
Read state data, such as joint positions and velocities, from the simulated robot hardware.
time | Simulation time. |
period | Time since the last simulation step. |
Implements gazebo_ros_control::RobotHWSim.
Definition at line 244 of file default_robot_hw_sim.cpp.
void gazebo_ros_control::DefaultRobotHWSim::registerJointLimits | ( | const std::string & | joint_name, |
const hardware_interface::JointHandle & | joint_handle, | ||
const ControlMethod | ctrl_method, | ||
const ros::NodeHandle & | joint_limit_nh, | ||
const urdf::Model *const | urdf_model, | ||
int *const | joint_type, | ||
double *const | lower_limit, | ||
double *const | upper_limit, | ||
double *const | effort_limit | ||
) | [protected] |
Definition at line 364 of file default_robot_hw_sim.cpp.
void gazebo_ros_control::DefaultRobotHWSim::writeSim | ( | ros::Time | time, |
ros::Duration | period | ||
) | [virtual] |
Write commands to the simulated robot hardware.
Write commands, such as joint position and velocity commands, to the simulated robot hardware.
time | Simulation time. |
period | Time since the last simulation step. |
Implements gazebo_ros_control::RobotHWSim.
Definition at line 263 of file default_robot_hw_sim.cpp.
bool gazebo_ros_control::DefaultRobotHWSim::e_stop_active_ [protected] |
Definition at line 138 of file default_robot_hw_sim.h.
hardware_interface::EffortJointInterface gazebo_ros_control::DefaultRobotHWSim::ej_interface_ [protected] |
Definition at line 109 of file default_robot_hw_sim.h.
joint_limits_interface::EffortJointSoftLimitsInterface gazebo_ros_control::DefaultRobotHWSim::ej_limits_interface_ [protected] |
Definition at line 114 of file default_robot_hw_sim.h.
joint_limits_interface::EffortJointSaturationInterface gazebo_ros_control::DefaultRobotHWSim::ej_sat_interface_ [protected] |
Definition at line 113 of file default_robot_hw_sim.h.
std::vector<ControlMethod> gazebo_ros_control::DefaultRobotHWSim::joint_control_methods_ [protected] |
Definition at line 125 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_effort_ [protected] |
Definition at line 129 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_effort_command_ [protected] |
Definition at line 130 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_effort_limits_ [protected] |
Definition at line 124 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_lower_limits_ [protected] |
Definition at line 122 of file default_robot_hw_sim.h.
std::vector<std::string> gazebo_ros_control::DefaultRobotHWSim::joint_names_ [protected] |
Definition at line 120 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_position_ [protected] |
Definition at line 127 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_position_command_ [protected] |
Definition at line 131 of file default_robot_hw_sim.h.
std::vector<int> gazebo_ros_control::DefaultRobotHWSim::joint_types_ [protected] |
Definition at line 121 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_upper_limits_ [protected] |
Definition at line 123 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_velocity_ [protected] |
Definition at line 128 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_velocity_command_ [protected] |
Definition at line 133 of file default_robot_hw_sim.h.
hardware_interface::JointStateInterface gazebo_ros_control::DefaultRobotHWSim::js_interface_ [protected] |
Definition at line 108 of file default_robot_hw_sim.h.
bool gazebo_ros_control::DefaultRobotHWSim::last_e_stop_active_ [protected] |
Definition at line 138 of file default_robot_hw_sim.h.
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::last_joint_position_command_ [protected] |
Definition at line 132 of file default_robot_hw_sim.h.
unsigned int gazebo_ros_control::DefaultRobotHWSim::n_dof_ [protected] |
Definition at line 106 of file default_robot_hw_sim.h.
std::vector<control_toolbox::Pid> gazebo_ros_control::DefaultRobotHWSim::pid_controllers_ [protected] |
Definition at line 126 of file default_robot_hw_sim.h.
hardware_interface::PositionJointInterface gazebo_ros_control::DefaultRobotHWSim::pj_interface_ [protected] |
Definition at line 110 of file default_robot_hw_sim.h.
joint_limits_interface::PositionJointSoftLimitsInterface gazebo_ros_control::DefaultRobotHWSim::pj_limits_interface_ [protected] |
Definition at line 116 of file default_robot_hw_sim.h.
joint_limits_interface::PositionJointSaturationInterface gazebo_ros_control::DefaultRobotHWSim::pj_sat_interface_ [protected] |
Definition at line 115 of file default_robot_hw_sim.h.
std::vector<gazebo::physics::JointPtr> gazebo_ros_control::DefaultRobotHWSim::sim_joints_ [protected] |
Definition at line 135 of file default_robot_hw_sim.h.
hardware_interface::VelocityJointInterface gazebo_ros_control::DefaultRobotHWSim::vj_interface_ [protected] |
Definition at line 111 of file default_robot_hw_sim.h.
joint_limits_interface::VelocityJointSoftLimitsInterface gazebo_ros_control::DefaultRobotHWSim::vj_limits_interface_ [protected] |
Definition at line 118 of file default_robot_hw_sim.h.
joint_limits_interface::VelocityJointSaturationInterface gazebo_ros_control::DefaultRobotHWSim::vj_sat_interface_ [protected] |
Definition at line 117 of file default_robot_hw_sim.h.