Class PumaHardware
Defined in File hardware.hpp
Inheritance Relationships
Base Type
public hardware_interface::SystemInterface
Class Documentation
-
class PumaHardware : public hardware_interface::SystemInterface
Public Functions
- HARDWARE_INTERFACE_PUBLIC hardware_interface::CallbackReturn on_init (const hardware_interface::HardwareInfo &info) override
- HARDWARE_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterface > export_state_interfaces () override
- HARDWARE_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterface > export_command_interfaces () override
- HARDWARE_INTERFACE_PUBLIC hardware_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
- HARDWARE_INTERFACE_PUBLIC hardware_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
- HARDWARE_INTERFACE_PUBLIC hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override
- HARDWARE_INTERFACE_PUBLIC hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period) override
Protected Functions
-
void writeCommandsToHardware()
-
void updateJointsFromHardware()
-
virtual hardware_interface::CallbackReturn getHardwareInfo(const hardware_interface::HardwareInfo &info)
-
virtual hardware_interface::CallbackReturn validateJoints()
-
virtual hardware_interface::CallbackReturn initHardwareInterface()
Protected Attributes
-
std::shared_ptr<PumaHardwareInterface> node_
-
std::vector<double> hw_commands_
-
std::vector<double> hw_states_position_
-
std::vector<double> hw_states_position_offset_
-
std::vector<double> hw_states_velocity_
-
std::map<std::string, uint8_t> wheel_joints_
-
uint8_t num_joints_
-
std::string hw_name_