#include <hardware_interface.h>
|
| RmRobotHW ()=default |
|
bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override |
| Get necessary params from param server. Init hardware_interface.
|
|
void | read (const ros::Time &time, const ros::Duration &period) override |
| Comunicate with hardware. Get datas, status of robot.
|
|
void | write (const ros::Time &time, const ros::Duration &period) override |
| Comunicate with hardware. Publish command to robot.
|
|
void | setCanBusThreadPriority (int thread_priority) |
|
◆ RmRobotHW()
rm_hw::RmRobotHW::RmRobotHW |
( |
| ) |
|
|
default |
◆ init()
bool rm_hw::RmRobotHW::init |
( |
ros::NodeHandle & | root_nh, |
|
|
ros::NodeHandle & | robot_hw_nh ) |
|
override |
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.
◆ read()
void rm_hw::RmRobotHW::read |
( |
const ros::Time & | time, |
|
|
const ros::Duration & | period ) |
|
override |
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 |
◆ setCanBusThreadPriority()
void rm_hw::RmRobotHW::setCanBusThreadPriority |
( |
int | thread_priority | ) |
|
◆ write()
void rm_hw::RmRobotHW::write |
( |
const ros::Time & | time, |
|
|
const ros::Duration & | period ) |
|
override |
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 |
The documentation for this class was generated from the following files: