This class defines a ros-control hardware interface. More...
#include <SchunkCanopenHardwareInterface.h>
This class defines a ros-control hardware interface.
Definition at line 48 of file SchunkCanopenHardwareInterface.h.
SchunkCanopenHardwareInterface::SchunkCanopenHardwareInterface | ( | ros::NodeHandle & | nh, |
boost::shared_ptr< CanOpenController > & | canopen | ||
) |
Definition at line 38 of file SchunkCanopenHardwareInterface.cpp.
void SchunkCanopenHardwareInterface::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 206 of file SchunkCanopenHardwareInterface.cpp.
sensor_msgs::JointState SchunkCanopenHardwareInterface::getJointMessage | ( | ) |
Creates a joint_state message from the current joint angles and returns it.
Definition at line 211 of file SchunkCanopenHardwareInterface.cpp.
void SchunkCanopenHardwareInterface::init | ( | ) | [virtual] |
Initialize the hardware interface.
Definition at line 46 of file SchunkCanopenHardwareInterface.cpp.
bool SchunkCanopenHardwareInterface::isFault | ( | ) | [inline] |
Returns true, when at least one node in the hardware is in a fault state.
Definition at line 71 of file SchunkCanopenHardwareInterface.h.
bool SchunkCanopenHardwareInterface::prepareSwitch | ( | 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 201 of file SchunkCanopenHardwareInterface.cpp.
void SchunkCanopenHardwareInterface::read | ( | ) | [virtual] |
Read the state from the robot hardware.
Definition at line 138 of file SchunkCanopenHardwareInterface.cpp.
void SchunkCanopenHardwareInterface::write | ( | ros::Time | time, |
ros::Duration | period | ||
) | [virtual] |
write the command to the robot hardware.
Definition at line 164 of file SchunkCanopenHardwareInterface.cpp.
boost::shared_ptr<CanOpenController> SchunkCanopenHardwareInterface::m_canopen_controller [protected] |
Definition at line 80 of file SchunkCanopenHardwareInterface.h.
bool SchunkCanopenHardwareInterface::m_is_fault [protected] |
Definition at line 98 of file SchunkCanopenHardwareInterface.h.
joint_limits_interface::PositionJointSoftLimitsInterface SchunkCanopenHardwareInterface::m_jnt_limits_interface [protected] |
Definition at line 85 of file SchunkCanopenHardwareInterface.h.
std::vector<double> SchunkCanopenHardwareInterface::m_joint_effort [protected] |
Definition at line 93 of file SchunkCanopenHardwareInterface.h.
Definition at line 100 of file SchunkCanopenHardwareInterface.h.
std::vector<std::string> SchunkCanopenHardwareInterface::m_joint_names [protected] |
Definition at line 90 of file SchunkCanopenHardwareInterface.h.
std::vector<double> SchunkCanopenHardwareInterface::m_joint_position_commands [protected] |
Definition at line 94 of file SchunkCanopenHardwareInterface.h.
std::vector<double> SchunkCanopenHardwareInterface::m_joint_position_commands_last [protected] |
Definition at line 95 of file SchunkCanopenHardwareInterface.h.
std::vector<double> SchunkCanopenHardwareInterface::m_joint_positions [protected] |
Definition at line 91 of file SchunkCanopenHardwareInterface.h.
joint_limits_interface::SoftJointLimits SchunkCanopenHardwareInterface::m_joint_soft_limits [protected] |
Definition at line 101 of file SchunkCanopenHardwareInterface.h.
hardware_interface::JointStateInterface SchunkCanopenHardwareInterface::m_joint_state_interface [protected] |
Definition at line 83 of file SchunkCanopenHardwareInterface.h.
std::vector<double> SchunkCanopenHardwareInterface::m_joint_velocity [protected] |
Definition at line 92 of file SchunkCanopenHardwareInterface.h.
Definition at line 79 of file SchunkCanopenHardwareInterface.h.
std::vector<uint8_t> SchunkCanopenHardwareInterface::m_node_ids [protected] |
Definition at line 89 of file SchunkCanopenHardwareInterface.h.
std::vector<bool> SchunkCanopenHardwareInterface::m_nodes_in_fault [protected] |
Definition at line 97 of file SchunkCanopenHardwareInterface.h.
size_t SchunkCanopenHardwareInterface::m_num_joints [protected] |
Definition at line 87 of file SchunkCanopenHardwareInterface.h.
hardware_interface::PositionJointInterface SchunkCanopenHardwareInterface::m_position_joint_interface [protected] |
Definition at line 84 of file SchunkCanopenHardwareInterface.h.