#include <default_robot_hw_sim.h>
|
virtual void | eStopActive (const bool active) |
| Set the emergency stop state. More...
|
|
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) |
| Initialize the simulated robot hardware. More...
|
|
virtual void | readSim (ros::Time time, ros::Duration period) |
| Read state data from the simulated robot hardware. More...
|
|
virtual void | writeSim (ros::Time time, ros::Duration period) |
| Write commands to the simulated robot hardware. More...
|
|
virtual | ~RobotHWSim () |
|
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
|
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
|
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
|
virtual bool | init (ros::NodeHandle &, ros::NodeHandle &) |
|
virtual bool | prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
|
virtual void | read (const ros::Time &, const ros::Duration &) |
|
virtual void | read (const ros::Time &, const ros::Duration &) |
|
virtual SwitchState | switchResult (const ControllerInfo &) const |
|
virtual SwitchState | switchResult () const |
|
virtual void | write (const ros::Time &, const ros::Duration &) |
|
virtual void | write (const ros::Time &, const ros::Duration &) |
|
virtual | ~RobotHW ()=default |
|
T * | get () |
|
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
|
std::vector< std::string > | getNames () const |
|
void | registerInterface (T *iface) |
|
void | registerInterfaceManager (InterfaceManager *iface_man) |
|
Definition at line 74 of file default_robot_hw_sim.h.
◆ ControlMethod
◆ eStopActive()
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.
- Parameters
-
active | true if the emergency stop is active, false if not. |
Reimplemented from gazebo_ros_control::RobotHWSim.
Definition at line 385 of file default_robot_hw_sim.cpp.
◆ initSim()
Initialize the simulated robot hardware.
Initialize the simulated robot hardware.
- Parameters
-
robot_namespace | Robot namespace. |
model_nh | Model node handle. |
parent_model | Parent model. |
urdf_model | URDF model. |
transmissions | Transmissions. |
- Returns
true
if the simulated robot hardware is initialized successfully, false
if not.
Implements gazebo_ros_control::RobotHWSim.
Definition at line 60 of file default_robot_hw_sim.cpp.
◆ readSim()
Read state data from the simulated robot hardware.
Read state data, such as joint positions and velocities, from the simulated robot hardware.
- Parameters
-
time | Simulation time. |
period | Time since the last simulation step. |
Implements gazebo_ros_control::RobotHWSim.
Definition at line 261 of file default_robot_hw_sim.cpp.
◆ registerJointLimits()
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 |
◆ writeSim()
Write commands to the simulated robot hardware.
Write commands, such as joint position and velocity commands, to the simulated robot hardware.
- Parameters
-
time | Simulation time. |
period | Time since the last simulation step. |
Implements gazebo_ros_control::RobotHWSim.
Definition at line 285 of file default_robot_hw_sim.cpp.
◆ e_stop_active_
bool gazebo_ros_control::DefaultRobotHWSim::e_stop_active_ |
|
protected |
◆ ej_interface_
◆ ej_limits_interface_
◆ ej_sat_interface_
◆ joint_control_methods_
std::vector<ControlMethod> gazebo_ros_control::DefaultRobotHWSim::joint_control_methods_ |
|
protected |
◆ joint_effort_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_effort_ |
|
protected |
◆ joint_effort_command_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_effort_command_ |
|
protected |
◆ joint_effort_limits_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_effort_limits_ |
|
protected |
◆ joint_lower_limits_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_lower_limits_ |
|
protected |
◆ joint_names_
std::vector<std::string> gazebo_ros_control::DefaultRobotHWSim::joint_names_ |
|
protected |
◆ joint_position_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_position_ |
|
protected |
◆ joint_position_command_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_position_command_ |
|
protected |
◆ joint_types_
std::vector<int> gazebo_ros_control::DefaultRobotHWSim::joint_types_ |
|
protected |
◆ joint_upper_limits_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_upper_limits_ |
|
protected |
◆ joint_velocity_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_velocity_ |
|
protected |
◆ joint_velocity_command_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::joint_velocity_command_ |
|
protected |
◆ js_interface_
◆ last_e_stop_active_
bool gazebo_ros_control::DefaultRobotHWSim::last_e_stop_active_ |
|
protected |
◆ last_joint_position_command_
std::vector<double> gazebo_ros_control::DefaultRobotHWSim::last_joint_position_command_ |
|
protected |
◆ n_dof_
unsigned int gazebo_ros_control::DefaultRobotHWSim::n_dof_ |
|
protected |
◆ physics_type_
std::string gazebo_ros_control::DefaultRobotHWSim::physics_type_ |
|
protected |
◆ pid_controllers_
◆ pj_interface_
◆ pj_limits_interface_
◆ pj_sat_interface_
◆ sim_joints_
std::vector<gazebo::physics::JointPtr> gazebo_ros_control::DefaultRobotHWSim::sim_joints_ |
|
protected |
◆ vj_interface_
◆ vj_limits_interface_
◆ vj_sat_interface_
The documentation for this class was generated from the following files: