36 #ifndef GAZEBO_ROS_KOBUKI_H 37 #define GAZEBO_ROS_KOBUKI_H 42 #include <boost/bind.hpp> 43 #include <boost/thread.hpp> 44 #include <boost/shared_ptr.hpp> 45 #include <gazebo/gazebo.hh> 46 #include <gazebo/common/common.hh> 47 #include <gazebo/common/Time.hh> 48 #if GAZEBO_MAJOR_VERSION >= 9 50 #include <ignition/math/Vector3.hh> 51 #include <ignition/math/Quaternion.hh> 53 #include <gazebo/math/gzmath.hh> 55 #include <gazebo/physics/physics.hh> 56 #include <gazebo/sensors/sensors.hh> 59 #include <std_msgs/Empty.h> 60 #include <std_msgs/Float64.h> 61 #include <sensor_msgs/Imu.h> 62 #include <sensor_msgs/JointState.h> 63 #include <nav_msgs/Odometry.h> 64 #include <geometry_msgs/Twist.h> 65 #include <geometry_msgs/TransformStamped.h> 68 #include <kobuki_msgs/MotorPower.h> 69 #include <kobuki_msgs/CliffEvent.h> 70 #include <kobuki_msgs/BumperEvent.h> 85 void Load(physics::ModelPtr parent, sdf::ElementPtr sdf);
94 void cmdVelCB(
const geometry_msgs::TwistConstPtr &
msg);
96 void motorPowerCB(
const kobuki_msgs::MotorPowerPtr &msg);
98 void resetOdomCB(
const std_msgs::EmptyConstPtr &msg);
238 #if GAZEBO_MAJOR_VERSION >= 9 bool cliff_detected_right_
Cliff flag for the right sensor.
double odom_pose_[3]
Vector for pose.
double torque_
Max. torque applied to the wheels.
void propagateVelocityCommands()
GazeboRosPtr gazebo_ros_
pointer to the gazebo ros node
float cliff_detection_threshold_
measured distance in meter for detecting a cliff
double wheel_sep_
Separation between the wheels.
bool shutdown_requested_
extra thread for triggering ROS callbacks
ros::Publisher imu_pub_
ROS publisher for IMU data.
sensors::RaySensorPtr cliff_sensor_center_
Pointer to frontal cliff sensor.
bool prepareWheelAndTorque()
void Load(physics::ModelPtr parent, sdf::ElementPtr sdf)
Called when plugin is loaded.
std::string tf_prefix_
TF Prefix.
bool bumper_center_was_pressed_
Flag for center bumper's last state.
ros::Subscriber cmd_vel_sub_
ROS subscriber for velocity commands.
bool cliff_detected_left_
Cliff flag for the left sensor.
sensors::ContactSensorPtr bumper_
Pointer to bumper sensor simulating Kobuki's left, centre and right bumper sensors.
physics::JointPtr joints_[2]
Pointers to Gazebo's joints.
bool prepareCliffSensor()
bool bumper_right_was_pressed_
Flag for right bumper's last state.
sensors::ImuSensorPtr imu_
Pointer to IMU sensor model.
GazeboRosKobuki()
Constructor.
void OnUpdate()
Called by the world update start event.
ros::Subscriber odom_reset_sub_
ROS subscriber for reseting the odometry data.
sensor_msgs::Imu imu_msg_
ROS message for publishing IMU data.
common::Time last_cmd_vel_time_
Simulation time of the last velocity command (used for time out)
ros::Publisher joint_state_pub_
ROS publisher for joint state messages.
bool bumper_left_is_pressed_
Flag for left bumper's current state.
double wheel_diam_
Diameter of the wheels.
bool prepareVelocityCommand()
void setupRosApi(std::string &model_name)
bool motors_enabled_
Flag indicating if the motors are turned on or not.
kobuki_msgs::BumperEvent bumper_event_
Kobuki ROS message for bumper event.
ros::Publisher bumper_event_pub_
ROS publisher for bumper events.
math::Vector3 vel_angular_
Storage for the angular velocity reported by the IMU.
physics::ModelPtr model_
pointer to the model
double wheel_speed_cmd_[2]
Speeds of the wheels.
int floot_dist_
Maximum distance to floor.
double * pose_cov_[36]
Pointer to pose covariance matrix.
void motorPowerCB(const kobuki_msgs::MotorPowerPtr &msg)
Callback for incoming velocity commands.
bool bumper_center_is_pressed_
Flag for left bumper's current state.
ros::Publisher odom_pub_
ROS publisher for odometry messages.
void spin()
Spin method for the spinner thread.
std::string right_wheel_joint_name_
Right wheel's joint name.
void resetOdomCB(const std_msgs::EmptyConstPtr &msg)
Callback for resetting the odometry data.
double cmd_vel_timeout_
Time out for velocity commands in seconds.
double odom_vel_[3]
Vector for velocity.
ros::NodeHandle nh_
ROS node handles (relative & private)
bool cliff_detected_center_
Cliff flag for the center sensor.
bool bumper_left_was_pressed_
Flag for left bumper's last state.
std::string left_wheel_joint_name_
Left wheel's joint name.
void cmdVelCB(const geometry_msgs::TwistConstPtr &msg)
Callback for incoming velocity commands.
geometry_msgs::TransformStamped odom_tf_
TF transform for the odom frame.
std::string node_name_
node name
kobuki_msgs::CliffEvent cliff_event_
Kobuki ROS message for cliff event.
void updateOdometry(common::Time &step_time)
sensors::RaySensorPtr cliff_sensor_left_
Pointer to left cliff sensor.
common::Time prev_update_time_
Simulation time on previous update.
double * twist_cov_[36]
Pointer to twist covariance matrix.
physics::WorldPtr world_
pointer to simulated world
ros::Publisher cliff_event_pub_
ROS publisher for cliff detection events.
bool bumper_right_is_pressed_
Flag for left bumper's current state.
bool publish_tf_
Flag for (not) publish tf transform for odom -> robot.
sensor_msgs::JointState joint_state_
ROS message for joint sates.
sensors::RaySensorPtr cliff_sensor_right_
Pointer to left right sensor.
nav_msgs::Odometry odom_
ROS message for odometry data.
~GazeboRosKobuki()
Destructor.
tf::TransformBroadcaster tf_broadcaster_
TF transform publisher for the odom frame.
ros::Subscriber motor_power_sub_
ROS subscriber for motor power commands.
event::ConnectionPtr update_connection_
pointer to the update event connection (triggers the OnUpdate callback when event update event is rec...