40 #ifndef GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H 41 #define GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H 44 #include <boost/scoped_ptr.hpp> 95 virtual bool canSwitch(
const std::list<hardware_interface::ControllerInfo> &start_list,
96 const std::list<hardware_interface::ControllerInfo> &stop_list)
const 106 virtual void doSwitch(
const std::list<hardware_interface::ControllerInfo> &start_list,
107 const std::list<hardware_interface::ControllerInfo> &stop_list)
120 std::size_t joint_id);
188 #endif // GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H hardware_interface::EffortJointInterface effort_joint_interface_
std::vector< double > joint_position_command_
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
Perform (in non-realtime) all necessary hardware interface switches in order to start and stop the gi...
virtual void read(ros::Duration &elapsed_time)=0
Read the state from the robot hardware.
hardware_interface::JointStateInterface joint_state_interface_
bool use_rosparam_joint_limits_
virtual void loadURDF(ros::NodeHandle &nh, std::string param_name)
Get the URDF XML from the parameter server.
std::vector< double > joint_position_lower_limits_
bool use_soft_limits_if_available_
std::vector< double > joint_effort_limits_
joint_limits_interface::EffortJointSaturationInterface eff_jnt_sat_interface_
virtual ~GenericHWInterface()
Destructor.
virtual void init()
Initialize the hardware interface.
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
std::vector< double > joint_effort_
virtual void registerJointLimits(const hardware_interface::JointHandle &joint_handle_position, const hardware_interface::JointHandle &joint_handle_velocity, const hardware_interface::JointHandle &joint_handle_effort, std::size_t joint_id)
Register the limits of the joint specified by joint_id and joint_handle. The limits are retrieved fro...
joint_limits_interface::VelocityJointSaturationInterface vel_jnt_sat_interface_
virtual void printState()
Helper for debugging a joint's state.
hardware_interface::VelocityJointInterface velocity_joint_interface_
joint_limits_interface::EffortJointSoftLimitsInterface eff_jnt_soft_limits_
std::vector< std::string > joint_names_
joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_soft_limits_
virtual void reset()
Set all members to default values.
std::string printCommandHelper()
Helper for debugging a joint's command.
virtual void write(ros::Duration &elapsed_time)=0
Write the command to the robot hardware.
std::vector< double > joint_position_upper_limits_
std::vector< double > joint_effort_command_
virtual bool canSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) const
Check (in non-realtime) if given controllers could be started and stopped from the current state of t...
std::string printStateHelper()
urdf::Model * urdf_model_
std::vector< double > joint_velocity_limits_
joint_limits_interface::VelocityJointSoftLimitsInterface vel_jnt_soft_limits_
std::vector< double > joint_position_
GenericHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor.
Hardware interface for a robot.
hardware_interface::PositionJointInterface position_joint_interface_
virtual void enforceLimits(ros::Duration &period)=0
joint_limits_interface::PositionJointSaturationInterface pos_jnt_sat_interface_