Public Member Functions | Protected Attributes
ros_control_ur::UrHardwareInterface Class Reference

Hardware interface for a robot. More...

#include <ur_hardware_interface.h>

Inheritance diagram for ros_control_ur::UrHardwareInterface:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool canSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) const
void doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
virtual void init ()
 Initialize the hardware interface.
virtual void read ()
 Read the state from the robot hardware.
void setMaxVelChange (double inp)
 UrHardwareInterface (ros::NodeHandle &nh, UrDriver *robot)
 Constructor.
virtual void write ()
 write the command to the robot hardware.

Protected Attributes

hardware_interface::ForceTorqueSensorInterface force_torque_interface_
std::vector< double > joint_effort_
std::vector< std::string > joint_names_
std::vector< double > joint_position_
std::vector< double > joint_position_command_
hardware_interface::JointStateInterface joint_state_interface_
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
double max_vel_change_
ros::NodeHandle nh_
std::size_t num_joints_
bool position_interface_running_
hardware_interface::PositionJointInterface position_joint_interface_
std::vector< double > prev_joint_velocity_command_
UrDriverrobot_
double robot_force_ [3] = { 0., 0., 0. }
double robot_torque_ [3] = { 0., 0., 0. }
bool velocity_interface_running_
hardware_interface::VelocityJointInterface velocity_joint_interface_

Detailed Description

Hardware interface for a robot.

Definition at line 79 of file ur_hardware_interface.h.


Constructor & Destructor Documentation

Constructor.

Parameters:
nh- Node handle for topics.

Definition at line 62 of file ur_hardware_interface.cpp.


Member Function Documentation

bool ros_control_ur::UrHardwareInterface::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 174 of file ur_hardware_interface.cpp.

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

Reimplemented from hardware_interface::RobotHW.

Definition at line 245 of file ur_hardware_interface.cpp.

Initialize the hardware interface.

Definition at line 72 of file ur_hardware_interface.cpp.

Read the state from the robot hardware.

Definition at line 131 of file ur_hardware_interface.cpp.

Definition at line 149 of file ur_hardware_interface.cpp.

write the command to the robot hardware.

Definition at line 153 of file ur_hardware_interface.cpp.


Member Data Documentation

Definition at line 112 of file ur_hardware_interface.h.

std::vector<double> ros_control_ur::UrHardwareInterface::joint_effort_ [protected]

Definition at line 121 of file ur_hardware_interface.h.

std::vector<std::string> ros_control_ur::UrHardwareInterface::joint_names_ [protected]

Definition at line 118 of file ur_hardware_interface.h.

Definition at line 119 of file ur_hardware_interface.h.

Definition at line 122 of file ur_hardware_interface.h.

Definition at line 111 of file ur_hardware_interface.h.

Definition at line 120 of file ur_hardware_interface.h.

Definition at line 123 of file ur_hardware_interface.h.

Definition at line 129 of file ur_hardware_interface.h.

Definition at line 108 of file ur_hardware_interface.h.

Definition at line 125 of file ur_hardware_interface.h.

Definition at line 116 of file ur_hardware_interface.h.

Definition at line 113 of file ur_hardware_interface.h.

Definition at line 124 of file ur_hardware_interface.h.

Definition at line 132 of file ur_hardware_interface.h.

double ros_control_ur::UrHardwareInterface::robot_force_[3] = { 0., 0., 0. } [protected]

Definition at line 126 of file ur_hardware_interface.h.

double ros_control_ur::UrHardwareInterface::robot_torque_[3] = { 0., 0., 0. } [protected]

Definition at line 127 of file ur_hardware_interface.h.

Definition at line 115 of file ur_hardware_interface.h.

Definition at line 114 of file ur_hardware_interface.h.


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


ur_modern_driver
Author(s): Thomas Timm Andersen
autogenerated on Wed Apr 3 2019 02:55:31