Go to the documentation of this file.
43 #include <unordered_map>
62 #include <rm_msgs/ActuatorState.h>
63 #include <rm_msgs/EnableImuTrigger.h>
177 bool enableImuTrigger(rm_msgs::EnableImuTrigger::Request& req, rm_msgs::EnableImuTrigger::Response& res);
209 std::unordered_map<std::string, std::unordered_map<int, ActData>>
bus_id2act_data_{};
212 std::unordered_map<std::string, std::unordered_map<int, ImuData>>
bus_id2imu_data_{};
215 std::unordered_map<std::string, std::unordered_map<int, TofData>>
bus_id2tof_data_{};
218 std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::ActuatorState>>
actuator_state_pub_;
transmission_interface::JointToActuatorEffortInterface * jnt_to_act_effort_
joint_limits_interface::EffortJointSaturationInterface effort_jnt_saturation_interface_
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::ActuatorState > > actuator_state_pub_
void publishActuatorState(const ros::Time &time)
Publish actuator's state to a topic named "/actuator_states".
std::unordered_map< std::string, std::unordered_map< int, TofData > > bus_id2tof_data_
rm_control::ActuatorExtraInterface act_extra_interface_
std::unordered_map< std::string, std::unordered_map< int, ImuData > > bus_id2imu_data_
bool parseActData(XmlRpc::XmlRpcValue &act_datas, ros::NodeHandle &robot_hw_nh)
Check whether actuator is specified and load specified params.
rm_control::GpioStateInterface gpio_state_interface_
std::vector< CanBus * > can_buses_
transmission_interface::ActuatorToJointStateInterface * act_to_jnt_state_
rm_control::RobotStateInterface robot_state_interface_
bool parseImuData(XmlRpc::XmlRpcValue &imu_datas, ros::NodeHandle &robot_hw_nh)
Check whether some params that are related to imu are set up and load these params.
bool loadUrdf(ros::NodeHandle &root_nh)
Load urdf of robot from param server.
bool parseGpioData(XmlRpc::XmlRpcValue &gpio_datas, ros::NodeHandle &robot_hw_nh)
Check whether somme params that are related to gpio are set up and load these params.
bool setupTransmission(ros::NodeHandle &root_nh)
Set up transmission.
joint_limits_interface::EffortJointSoftLimitsInterface effort_jnt_soft_limits_interface_
std::unordered_map< std::string, ActCoeff > type2act_coeffs_
std::shared_ptr< urdf::Model > urdf_model_
rm_control::GpioCommandInterface gpio_command_interface_
hardware_interface::ImuSensorInterface imu_sensor_interface_
ros::ServiceServer service_server_
bool parseTofData(XmlRpc::XmlRpcValue &tof_datas, ros::NodeHandle &robot_hw_nh)
bool enableImuTrigger(rm_msgs::EnableImuTrigger::Request &req, rm_msgs::EnableImuTrigger::Response &res)
void setCanBusThreadPriority(int thread_priority)
std::unordered_map< std::string, std::unordered_map< int, ActData > > bus_id2act_data_
std::vector< hardware_interface::JointHandle > effort_joint_handles_
GpioManager gpio_manager_
transmission_interface::RobotTransmissions robot_transmissions_
void read(const ros::Time &time, const ros::Duration &period) override
Comunicate with hardware. Get datas, status of robot.
rm_control::TofRadarInterface tof_radar_interface_
rm_control::RmImuSensorInterface rm_imu_sensor_interface_
hardware_interface::ActuatorStateInterface act_state_interface_
bool is_actuator_specified_
ros::Time last_publish_time_
std::unique_ptr< transmission_interface::TransmissionInterfaceLoader > transmission_loader_
bool setupJointLimit(ros::NodeHandle &root_nh)
Set up joint limit.
bool parseActCoeffs(XmlRpc::XmlRpcValue &act_coeffs)
Check whether some coefficients that are related to actuator are set up and load these coefficients.
hardware_interface::EffortActuatorInterface effort_act_interface_
void write(const ros::Time &time, const ros::Duration &period) override
Comunicate with hardware. Publish command to robot.
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Get necessary params from param server. Init hardware_interface.
rm_hw
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:44