Public Types | Public Member Functions | Public Attributes | Private Member Functions
YumiHW Class Reference

#include <yumi_hw.h>

Inheritance diagram for YumiHW:
Inheritance graph
[legend]

List of all members.

Public Types

enum  ControlStrategy { JOINT_POSITION = 10, JOINT_VELOCITY = 15 }

Public Member Functions

virtual bool canSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) const
void create (std::string name, std::string urdf_string)
virtual void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
void enforceLimits (ros::Duration period)
ControlStrategy getControlStrategy ()
virtual bool init ()=0
virtual void read (ros::Time time, ros::Duration period)=0
void reset ()
void setControlStrategy (ControlStrategy strategy)
virtual void write (ros::Time time, ros::Duration period)=0
 YumiHW ()
virtual ~YumiHW ()

Public Attributes

ControlStrategy current_strategy_
std::vector< double > joint_effort_
std::vector< double > joint_lower_limits_
std::vector< std::string > joint_names_
std::vector< double > joint_position_
std::vector< double > joint_position_command_
std::vector< double > joint_position_prev_
std::vector< double > joint_upper_limits_
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
int n_joints_
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
hardware_interface::PositionJointInterface position_interface_
std::string robot_namespace_
hardware_interface::JointStateInterface state_interface_
std::vector
< transmission_interface::TransmissionInfo
transmissions_
urdf::Model urdf_model_
std::string urdf_string_
hardware_interface::VelocityJointInterface velocity_interface_
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_

Private Member Functions

bool parseTransmissionsFromURDF (const std::string &urdf_string)
void registerInterfaces (const urdf::Model *const urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions)
void registerJointLimits (const std::string &joint_name, const hardware_interface::JointHandle &joint_handle_position, const hardware_interface::JointHandle &joint_handle_velocity, const urdf::Model *const urdf_model, double *const lower_limit, double *const upper_limit)

Detailed Description

Base class for yumi hw interface. Extended later for gazebo and for real robot over rapid

Definition at line 34 of file yumi_hw.h.


Member Enumeration Documentation

Enumerator:
JOINT_POSITION 
JOINT_VELOCITY 

Definition at line 57 of file yumi_hw.h.


Constructor & Destructor Documentation

YumiHW::YumiHW ( ) [inline]

Definition at line 38 of file yumi_hw.h.

virtual YumiHW::~YumiHW ( ) [inline, virtual]

Definition at line 42 of file yumi_hw.h.


Member Function Documentation

bool YumiHW::canSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
) const [virtual]

Reimplemented from hardware_interface::RobotHW.

Definition at line 315 of file yumi_hw.cpp.

void YumiHW::create ( std::string  name,
std::string  urdf_string 
)

Definition at line 3 of file yumi_hw.cpp.

void YumiHW::doSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
) [virtual]

semantic Zero

call setCommand once so that the JointLimitsInterface receive the correct value on their getCommand()!

reset joint_limit_interfaces

Reimplemented from hardware_interface::RobotHW.

Definition at line 352 of file yumi_hw.cpp.

Definition at line 440 of file yumi_hw.cpp.

Definition at line 68 of file yumi_hw.h.

virtual bool YumiHW::init ( ) [pure virtual]

Implemented in YumiHWRapid, and YumiHWGazebo.

bool YumiHW::parseTransmissionsFromURDF ( const std::string &  urdf_string) [private]

Definition at line 231 of file yumi_hw.cpp.

virtual void YumiHW::read ( ros::Time  time,
ros::Duration  period 
) [pure virtual]

Implemented in YumiHWRapid, and YumiHWGazebo.

void YumiHW::registerInterfaces ( const urdf::Model *const  urdf_model,
std::vector< transmission_interface::TransmissionInfo transmissions 
) [private]

Definition at line 85 of file yumi_hw.cpp.

void YumiHW::registerJointLimits ( const std::string &  joint_name,
const hardware_interface::JointHandle joint_handle_position,
const hardware_interface::JointHandle joint_handle_velocity,
const urdf::Model *const  urdf_model,
double *const  lower_limit,
double *const  upper_limit 
) [private]

Definition at line 171 of file yumi_hw.cpp.

void YumiHW::reset ( )

Definition at line 66 of file yumi_hw.cpp.

void YumiHW::setControlStrategy ( ControlStrategy  strategy) [inline]

Definition at line 67 of file yumi_hw.h.

virtual void YumiHW::write ( ros::Time  time,
ros::Duration  period 
) [pure virtual]

Implemented in YumiHWRapid, and YumiHWGazebo.


Member Data Documentation

Definition at line 76 of file yumi_hw.h.

std::vector<double> YumiHW::joint_effort_

Definition at line 100 of file yumi_hw.h.

std::vector<double> YumiHW::joint_lower_limits_

Definition at line 95 of file yumi_hw.h.

std::vector<std::string> YumiHW::joint_names_

Definition at line 91 of file yumi_hw.h.

std::vector<double> YumiHW::joint_position_

Definition at line 100 of file yumi_hw.h.

std::vector<double> YumiHW::joint_position_command_

Definition at line 100 of file yumi_hw.h.

std::vector<double> YumiHW::joint_position_prev_

Definition at line 100 of file yumi_hw.h.

std::vector<double> YumiHW::joint_upper_limits_

Definition at line 95 of file yumi_hw.h.

std::vector<double> YumiHW::joint_velocity_

Definition at line 100 of file yumi_hw.h.

std::vector<double> YumiHW::joint_velocity_command_

Definition at line 100 of file yumi_hw.h.

Definition at line 90 of file yumi_hw.h.

Definition at line 84 of file yumi_hw.h.

Definition at line 83 of file yumi_hw.h.

Definition at line 73 of file yumi_hw.h.

Definition at line 47 of file yumi_hw.h.

Definition at line 68 of file yumi_hw.h.

Definition at line 111 of file yumi_hw.h.

Definition at line 51 of file yumi_hw.h.

std::string YumiHW::urdf_string_

Definition at line 50 of file yumi_hw.h.

Definition at line 74 of file yumi_hw.h.

Definition at line 82 of file yumi_hw.h.

Definition at line 81 of file yumi_hw.h.


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


yumi_hw
Author(s):
autogenerated on Sat Jun 8 2019 20:47:40