62 bool initSim(
const std::string& robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model,
63 const urdf::Model* urdf_model,
64 std::vector<transmission_interface::TransmissionInfo> transmissions)
override;
65 void readSim(ros::Time time, ros::Duration period)
override;
68 void parseImu(XmlRpc::XmlRpcValue& imu_datas,
const gazebo::physics::ModelPtr& parent_model);
70 static bool switchImuStatus(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
72 disable_imu_ = !disable_imu_;
74 std::string imu_status_message = disable_imu_ ?
"disable" :
"enable";
75 res.message =
"Imu status: " + imu_status_message;
79 hardware_interface::ImuSensorInterface imu_sensor_interface_;
81 gazebo::physics::WorldPtr world_;
82 std::list<ImuData> imu_datas_;
83 ros::ServiceServer switch_imu_service_;
84 static bool disable_imu_;