Class KukaMockHardwareInterface
Defined in File hardware_interface.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public hardware_interface::SystemInterface
Class Documentation
-
class KukaMockHardwareInterface : public hardware_interface::SystemInterface
Public Functions
-
CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
-
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
-
std::vector<hardware_interface::StateInterface> export_state_interfaces() override
-
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override
-
return_type prepare_command_mode_switch(const std::vector<std::string> &start_interfaces, const std::vector<std::string> &stop_interfaces) override
-
return_type perform_command_mode_switch(const std::vector<std::string> &start_interfaces, const std::vector<std::string> &stop_interfaces) override
-
return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
-
return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Protected Attributes
-
const std::vector<std::string> standard_interfaces_ = {hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY, hardware_interface::HW_IF_ACCELERATION, hardware_interface::HW_IF_EFFORT}
Use standard interfaces for joints because they are relevant for dynamic behavior.
By splitting the standard interfaces from other type, the users are able to inherit this class and simply create small “simulation” with desired dynamic behavior. The advantage over using Gazebo is that enables “quick & dirty” tests of robot’s URDF and controllers.
-
std::vector<MimicJoint> mimic_joints_
-
std::vector<std::vector<double>> joint_commands_
The size of this vector is (standard_interfaces_.size() x nr_joints)
-
std::vector<std::vector<double>> joint_states_
-
std::vector<std::string> other_interfaces_
-
std::vector<std::vector<double>> other_commands_
The size of this vector is (other_interfaces_.size() x nr_joints)
-
std::vector<std::vector<double>> other_states_
-
std::vector<std::string> sensor_interfaces_
-
std::vector<std::vector<double>> sensor_mock_commands_
The size of this vector is (sensor_interfaces_.size() x nr_joints)
-
std::vector<std::vector<double>> sensor_states_
-
std::vector<std::string> gpio_interfaces_
-
std::vector<std::vector<double>> gpio_mock_commands_
The size of this vector is (gpio_interfaces_.size() x nr_joints)
-
std::vector<std::vector<double>> gpio_commands_
-
std::vector<std::vector<double>> gpio_states_
-
RobotState robot_state_
-
double control_mode_ = 0
-
double receive_multiplier_ = 1
-
double send_period_ms_ = 10
-
double cycle_time_ms_ = 4
-
double drive_state_ = 0.0
-
double server_state_ = 0.0
-
double control_mode_state_ = 0.0
-
double cycle_time_state_ = 0.0
-
double drives_powered_ = 0.0
-
double emergency_stop_ = 0.0
-
double guard_stop_ = 0.0
-
double in_motion_ = 0.0
-
double motion_possible_ = 0.0
-
double operation_mode_ = 0.0
-
double robot_stopped_ = 1.0
-
std::chrono::nanoseconds cycle_time_nano_
-
int roundtrip_time_micro_
-
bool init_clock_ = true
-
std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds> next_iteration_time_
-
struct MimicJoint
-
struct RobotState
-
CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override