#include <hardware_interface.h>
Definition at line 101 of file hardware_interface.h.
◆ RmRobotHW()
rm_hw::RmRobotHW::RmRobotHW |
( |
| ) |
|
|
default |
◆ enableImuTrigger()
bool rm_hw::RmRobotHW::enableImuTrigger |
( |
rm_msgs::EnableImuTrigger::Request & |
req, |
|
|
rm_msgs::EnableImuTrigger::Response & |
res |
|
) |
| |
|
private |
◆ init()
Get necessary params from param server. Init hardware_interface.
Get params from param server and check whether these params are set. Load urdf of robot. Set up transmission and joint limit. Get configuration of can bus and create data pointer which point to data received from Can bus.
- Parameters
-
root_nh | Root node-handle of a ROS node. |
robot_hw_nh | Node-handle for robot hardware. |
- Returns
- True when init successful, False when failed.
Reimplemented from hardware_interface::RobotHW.
Definition at line 75 of file hardware_interface.cpp.
◆ loadUrdf()
Load urdf of robot from param server.
Load urdf of robot from param server.
- Parameters
-
root_nh | Root node-handle of a ROS node |
- Returns
- True if successful.
Definition at line 525 of file parse.cpp.
◆ parseActCoeffs()
Check whether some coefficients that are related to actuator are set up and load these coefficients.
Check whether some coefficients that are related to actuator are set up and load these coefficients.
- Parameters
-
act_coeffs | Coefficients you want to check and load. |
- Returns
- True if all coefficients are set up.
Definition at line 81 of file parse.cpp.
◆ parseActData()
Check whether actuator is specified and load specified params.
Check whether actuator is specified and load specified params.
- Parameters
-
act_datas | Params you want to check and load. |
robot_hw_nh | Root node-handle of a ROS node. |
- Returns
- True if all params are set up.
Definition at line 159 of file parse.cpp.
◆ parseGpioData()
Check whether somme params that are related to gpio are set up and load these params.
Check whether somme params that are related to gpio are set up and load these params.
- Parameters
-
gpio_datas | Params you want to check and load |
robot_hw_nh | A handle of a ROS node |
- Returns
- True if all params are set up.
Definition at line 431 of file parse.cpp.
◆ parseImuData()
Check whether some params that are related to imu are set up and load these params.
Check whether some params that are related to imu are set up and load these params.
- Parameters
-
imu_datas | Params you want to check |
robot_hw_nh | Root node-handle of a ROS node |
- Returns
- True if all params are set up.
Definition at line 269 of file parse.cpp.
◆ parseTofData()
◆ publishActuatorState()
void rm_hw::RmRobotHW::publishActuatorState |
( |
const ros::Time & |
time | ) |
|
|
private |
Publish actuator's state to a topic named "/actuator_states".
Publish actuator's state to a topic named "/actuator_states".
- Parameters
-
Definition at line 216 of file hardware_interface.cpp.
◆ read()
Comunicate with hardware. Get datas, status of robot.
Call rm_hw::CanBus::read(). Check whether temperature of actuator is too high and whether actuator is offline. Propagate actuator state to joint state for the stored transmission. Set all cmd to zero to avoid crazy soft limit oscillation when not controller loaded(all controllers update after read()).
- Parameters
-
time | Current time |
period | Current time - last time |
Reimplemented from hardware_interface::RobotHW.
Definition at line 152 of file hardware_interface.cpp.
◆ setCanBusThreadPriority()
void rm_hw::RmRobotHW::setCanBusThreadPriority |
( |
int |
thread_priority | ) |
|
◆ setupJointLimit()
Set up joint limit.
Set up joint limit.
- Parameters
-
root_nh | Root node-handle of a ROS node. |
- Returns
- True if successful.
Definition at line 575 of file parse.cpp.
◆ setupTransmission()
Set up transmission.
Set up transmission
- Parameters
-
root_nh | Root node-handle of a ROS node. |
- Returns
- True if successful.
Definition at line 534 of file parse.cpp.
◆ write()
Comunicate with hardware. Publish command to robot.
Propagate joint state to actuator state for the stored transmission. Limit cmd_effort into suitable value. Call rm_hw::CanBus::write(). Publish actuator current state.
- Parameters
-
time | Current time |
period | Current time - last time |
Reimplemented from hardware_interface::RobotHW.
Definition at line 183 of file hardware_interface.cpp.
◆ act_extra_interface_
◆ act_state_interface_
◆ act_to_jnt_state_
◆ actuator_state_pub_
◆ bus_id2act_data_
std::unordered_map<std::string, std::unordered_map<int, ActData> > rm_hw::RmRobotHW::bus_id2act_data_ {} |
|
private |
◆ bus_id2imu_data_
std::unordered_map<std::string, std::unordered_map<int, ImuData> > rm_hw::RmRobotHW::bus_id2imu_data_ {} |
|
private |
◆ bus_id2tof_data_
std::unordered_map<std::string, std::unordered_map<int, TofData> > rm_hw::RmRobotHW::bus_id2tof_data_ {} |
|
private |
◆ can_buses_
std::vector<CanBus*> rm_hw::RmRobotHW::can_buses_ {} |
|
private |
◆ effort_act_interface_
◆ effort_jnt_saturation_interface_
◆ effort_jnt_soft_limits_interface_
◆ effort_joint_handles_
◆ gpio_command_interface_
◆ gpio_manager_
◆ gpio_state_interface_
◆ imu_sensor_interface_
◆ is_actuator_specified_
bool rm_hw::RmRobotHW::is_actuator_specified_ = false |
|
private |
◆ jnt_to_act_effort_
◆ last_publish_time_
ros::Time rm_hw::RmRobotHW::last_publish_time_ |
|
private |
◆ rm_imu_sensor_interface_
◆ robot_state_interface_
◆ robot_transmissions_
◆ service_server_
◆ thread_priority_
int rm_hw::RmRobotHW::thread_priority_ |
|
private |
◆ tof_radar_interface_
◆ transmission_loader_
◆ type2act_coeffs_
std::unordered_map<std::string, ActCoeff> rm_hw::RmRobotHW::type2act_coeffs_ {} |
|
private |
◆ urdf_model_
std::shared_ptr<urdf::Model> rm_hw::RmRobotHW::urdf_model_ |
|
private |
◆ urdf_string_
std::string rm_hw::RmRobotHW::urdf_string_ |
|
private |
The documentation for this class was generated from the following files: