40#include <gazebo_ros_control/default_robot_hw_sim.h>
44#include <std_srvs/Trigger.h>
50 hardware_interface::JointHandle
joint_;
75 bool initSim(
const std::string& robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model,
76 const urdf::Model* urdf_model,
77 std::vector<transmission_interface::TransmissionInfo> transmissions)
override;
78 void readSim(ros::Time time, ros::Duration period)
override;
79 void writeSim(ros::Time time, ros::Duration period)
override;
82 void parseImu(XmlRpc::XmlRpcValue& imu_datas,
const gazebo::physics::ModelPtr& parent_model);
84 static bool switchImuStatus(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
86 disable_imu_ = !disable_imu_;
88 std::string imu_status_message = disable_imu_ ?
"disable" :
"enable";
89 res.message =
"Imu status: " + imu_status_message;
95 hardware_interface::ImuSensorInterface imu_sensor_interface_;
97 gazebo::physics::WorldPtr world_;
98 std::list<ImuData> imu_datas_;
99 ros::ServiceServer switch_imu_service_;
101 std::list<HybridJointData> hybridJointDatas_;
102 std::unordered_map<std::string, std::deque<HybridJointCommand> > cmdBuffer_;
104 static bool disable_imu_;
Definition hybrid_joint_interface.h:113
Definition rm_imu_sensor_interface.h:36
Definition robot_state_interface.h:93
Definition rm_robot_hw_sim.h:73
bool initSim(const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions) override
Definition rm_robot_hw_sim.cpp:44
void writeSim(ros::Time time, ros::Duration period) override
Definition rm_robot_hw_sim.cpp:117
void readSim(ros::Time time, ros::Duration period) override
Definition rm_robot_hw_sim.cpp:75
Definition rm_robot_hw_sim.h:47
Definition rm_robot_hw_sim.h:55
double kd_
Definition rm_robot_hw_sim.h:57
double ff_
Definition rm_robot_hw_sim.h:57
double kp_
Definition rm_robot_hw_sim.h:57
double velDes_
Definition rm_robot_hw_sim.h:57
double posDes_
Definition rm_robot_hw_sim.h:57
ros::Time stamp_
Definition rm_robot_hw_sim.h:56
Definition rm_robot_hw_sim.h:49
double kp_
Definition rm_robot_hw_sim.h:51
double velDes_
Definition rm_robot_hw_sim.h:51
double posDes_
Definition rm_robot_hw_sim.h:51
double kd_
Definition rm_robot_hw_sim.h:51
double ff_
Definition rm_robot_hw_sim.h:51
hardware_interface::JointHandle joint_
Definition rm_robot_hw_sim.h:50
Definition rm_robot_hw_sim.h:61
double linear_acc[3]
Definition rm_robot_hw_sim.h:68
ros::Time time_stamp
Definition rm_robot_hw_sim.h:63
double ori[4]
Definition rm_robot_hw_sim.h:64
double angular_vel[3]
Definition rm_robot_hw_sim.h:66
double angular_vel_cov[9]
Definition rm_robot_hw_sim.h:67
double ori_cov[9]
Definition rm_robot_hw_sim.h:65
gazebo::physics::LinkPtr link_ptr
Definition rm_robot_hw_sim.h:62
double linear_acc_cov[9]
Definition rm_robot_hw_sim.h:69