83 bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh)
override;
93 void read(
const ros::Time& time,
const ros::Duration& period)
override;
103 void write(
const ros::Time& time,
const ros::Duration& period)
override;
115 bool parseActCoeffs(XmlRpc::XmlRpcValue& act_coeffs);
124 bool parseActData(XmlRpc::XmlRpcValue& act_datas, ros::NodeHandle& robot_hw_nh);
133 bool parseImuData(XmlRpc::XmlRpcValue& imu_datas, ros::NodeHandle& robot_hw_nh);
142 bool parseGpioData(XmlRpc::XmlRpcValue& gpio_datas, ros::NodeHandle& robot_hw_nh);
150 bool loadUrdf(ros::NodeHandle& root_nh);
152 bool parseTofData(XmlRpc::XmlRpcValue& tof_datas, ros::NodeHandle& robot_hw_nh);
160 bool setupTransmission(ros::NodeHandle& root_nh);
168 bool setupJointLimit(ros::NodeHandle& root_nh);
175 void publishActuatorState(
const ros::Time& time);
177 bool enableImuTrigger(rm_msgs::EnableImuTrigger::Request& req, rm_msgs::EnableImuTrigger::Response& res);
179 ros::ServiceServer service_server_;
181 bool is_actuator_specified_ =
false;
182 int thread_priority_;
184 std::vector<CanBus*> can_buses_{};
188 hardware_interface::ActuatorStateInterface act_state_interface_;
190 hardware_interface::EffortActuatorInterface effort_act_interface_;
192 hardware_interface::ImuSensorInterface imu_sensor_interface_;
194 std::unique_ptr<transmission_interface::TransmissionInterfaceLoader> transmission_loader_{};
195 transmission_interface::RobotTransmissions robot_transmissions_;
196 transmission_interface::ActuatorToJointStateInterface* act_to_jnt_state_{};
197 transmission_interface::JointToActuatorEffortInterface* jnt_to_act_effort_{};
198 joint_limits_interface::EffortJointSaturationInterface effort_jnt_saturation_interface_;
199 joint_limits_interface::EffortJointSoftLimitsInterface effort_jnt_soft_limits_interface_;
200 std::vector<hardware_interface::JointHandle> effort_joint_handles_{};
204 std::string urdf_string_;
205 std::shared_ptr<urdf::Model> urdf_model_;
208 std::unordered_map<std::string, ActCoeff> type2act_coeffs_{};
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_{};
217 ros::Time last_publish_time_;
218 std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::ActuatorState>> actuator_state_pub_;
void write(const ros::Time &time, const ros::Duration &period) override
Comunicate with hardware. Publish command to robot.
Definition hardware_interface.cpp:152
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Get necessary params from param server. Init hardware_interface.
Definition hardware_interface.cpp:44
void read(const ros::Time &time, const ros::Duration &period) override
Comunicate with hardware. Get datas, status of robot.
Definition hardware_interface.cpp:121