Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
gazebo_ros_control::Armadillo2RobotHWSim Class Reference

#include <armadillo2_sim_interface.h>

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

List of all members.

Public Member Functions

virtual void eStopActive (const bool active)
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)
virtual void readSim (ros::Time time, ros::Duration period)
virtual void writeSim (ros::Time time, ros::Duration period)

Protected Types

enum  ControlMethod {
  EFFORT, POSITION, POSITION_PID, VELOCITY,
  VELOCITY_PID, POS_VEL
}

Protected Member Functions

void 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)
void registerJointLimits (const std::string &joint_name, const hardware_interface::PosVelJointHandle &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 Attributes

bool e_stop_active_
hardware_interface::EffortJointInterface ej_interface_
joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_
joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_
std::vector< ControlMethodjoint_control_methods_
std::vector< double > joint_effort_
std::vector< double > joint_effort_command_
std::vector< double > joint_effort_limits_
std::vector< double > joint_lower_limits_
std::vector< std::stringjoint_names_
std::vector< double > joint_position_
std::vector< double > joint_position_command_
std::vector< int > joint_types_
std::vector< double > joint_upper_limits_
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
hardware_interface::JointStateInterface js_interface_
bool last_e_stop_active_
std::vector< double > last_joint_position_command_
unsigned int n_dof_
std::vector< control_toolbox::Pidpid_controllers_
hardware_interface::PositionJointInterface pj_interface_
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
hardware_interface::PosVelJointInterface pvj_interface_
std::vector
< gazebo::physics::JointPtr > 
sim_joints_
hardware_interface::VelocityJointInterface vj_interface_
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_

Detailed Description

Definition at line 37 of file armadillo2_sim_interface.h.


Member Enumeration Documentation

Enumerator:
EFFORT 
POSITION 
POSITION_PID 
VELOCITY 
VELOCITY_PID 
POS_VEL 

Definition at line 56 of file armadillo2_sim_interface.h.


Member Function Documentation

void gazebo_ros_control::Armadillo2RobotHWSim::eStopActive ( const bool  active) [virtual]

Reimplemented from gazebo_ros_control::RobotHWSim.

Definition at line 341 of file armadillo2_sim_interface.cpp.

bool gazebo_ros_control::Armadillo2RobotHWSim::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]

Implements gazebo_ros_control::RobotHWSim.

Definition at line 19 of file armadillo2_sim_interface.cpp.

Implements gazebo_ros_control::RobotHWSim.

Definition at line 222 of file armadillo2_sim_interface.cpp.

void gazebo_ros_control::Armadillo2RobotHWSim::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 349 of file armadillo2_sim_interface.cpp.

void gazebo_ros_control::Armadillo2RobotHWSim::registerJointLimits ( const std::string joint_name,
const hardware_interface::PosVelJointHandle 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 469 of file armadillo2_sim_interface.cpp.

Implements gazebo_ros_control::RobotHWSim.

Definition at line 241 of file armadillo2_sim_interface.cpp.


Member Data Documentation

Definition at line 111 of file armadillo2_sim_interface.h.

Definition at line 80 of file armadillo2_sim_interface.h.

Definition at line 86 of file armadillo2_sim_interface.h.

Definition at line 85 of file armadillo2_sim_interface.h.

Definition at line 98 of file armadillo2_sim_interface.h.

Definition at line 102 of file armadillo2_sim_interface.h.

Definition at line 103 of file armadillo2_sim_interface.h.

Definition at line 97 of file armadillo2_sim_interface.h.

Definition at line 95 of file armadillo2_sim_interface.h.

Definition at line 93 of file armadillo2_sim_interface.h.

Definition at line 100 of file armadillo2_sim_interface.h.

Definition at line 104 of file armadillo2_sim_interface.h.

Definition at line 94 of file armadillo2_sim_interface.h.

Definition at line 96 of file armadillo2_sim_interface.h.

Definition at line 101 of file armadillo2_sim_interface.h.

Definition at line 106 of file armadillo2_sim_interface.h.

Definition at line 79 of file armadillo2_sim_interface.h.

Definition at line 111 of file armadillo2_sim_interface.h.

Definition at line 105 of file armadillo2_sim_interface.h.

Definition at line 77 of file armadillo2_sim_interface.h.

Definition at line 99 of file armadillo2_sim_interface.h.

Definition at line 81 of file armadillo2_sim_interface.h.

Definition at line 88 of file armadillo2_sim_interface.h.

Definition at line 87 of file armadillo2_sim_interface.h.

Definition at line 83 of file armadillo2_sim_interface.h.

std::vector<gazebo::physics::JointPtr> gazebo_ros_control::Armadillo2RobotHWSim::sim_joints_ [protected]

Definition at line 108 of file armadillo2_sim_interface.h.

Definition at line 82 of file armadillo2_sim_interface.h.

Definition at line 90 of file armadillo2_sim_interface.h.

Definition at line 89 of file armadillo2_sim_interface.h.


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


robotican_hardware_interface
Author(s):
autogenerated on Fri Oct 27 2017 03:02:48