diff --git a/gazebo_plugins/CMakeLists.txt b/gazebo_plugins/CMakeLists.txt index 7f5a56c64..88c338f23 100644 --- a/gazebo_plugins/CMakeLists.txt +++ b/gazebo_plugins/CMakeLists.txt @@ -186,6 +186,22 @@ ament_target_dependencies(gazebo_ros_ft_sensor ) ament_export_libraries(gazebo_ros_ft_sensor) +# gazebo_ros_ackermann_drive +add_library(gazebo_ros_ackermann_drive SHARED + src/gazebo_ros_ackermann_drive.cpp +) +ament_target_dependencies(gazebo_ros_ackermann_drive + "gazebo_dev" + "gazebo_ros" + "geometry_msgs" + "nav_msgs" + "rclcpp" + "tf2" + "tf2_geometry_msgs" + "tf2_ros" +) +ament_export_libraries(gazebo_ros_ackermann_drive) + # gazebo_ros_elevator add_library(gazebo_ros_elevator SHARED src/gazebo_ros_elevator.cpp @@ -218,6 +234,7 @@ install(DIRECTORY include/ DESTINATION include) install(TARGETS + gazebo_ros_ackermann_drive gazebo_ros_camera gazebo_ros_diff_drive gazebo_ros_elevator diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_ackermann_drive.hpp b/gazebo_plugins/include/gazebo_plugins/gazebo_ros_ackermann_drive.hpp new file mode 100644 index 000000000..4d1c90d4f --- /dev/null +++ b/gazebo_plugins/include/gazebo_plugins/gazebo_ros_ackermann_drive.hpp @@ -0,0 +1,103 @@ +// Copyright 2019 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef GAZEBO_PLUGINS__GAZEBO_ROS_ACKERMANN_DRIVE_HPP_ +#define GAZEBO_PLUGINS__GAZEBO_ROS_ACKERMANN_DRIVE_HPP_ + +#include + +#include + +namespace gazebo_plugins +{ +class GazeboRosAckermannDrivePrivate; + +/// A ackermann drive plugin for car like robots. Subscribes to geometry_msgs/twist + +/** + Example Usage: + \code{.xml} + + + + demo + cmd_vel:=cmd_demo + odom:=odom_demo + distance:=distance_demo + + + 100.0 + + + front_left_wheel_joint + front_right_wheel_joint + rear_left_wheel_joint + rear_right_wheel_joint + front_left_steer_joint + front_right_steer_joint + steering_joint + + + + 0.6458 + + + 7.85 + + + 20 + + + 1500 0 1 + 0 0 + 1500 0 1 + 0 0 + 1000 0 1 + 0 0 + + + true + true + true + true + + odom_demo + chassis + + + \endcode +*/ +class GazeboRosAckermannDrive : public gazebo::ModelPlugin +{ +public: + /// Constructor + GazeboRosAckermannDrive(); + + /// Destructor + ~GazeboRosAckermannDrive(); + +protected: + // Documentation inherited + void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override; + + // Documentation inherited + void Reset() override; + +private: + /// Private data pointer + std::unique_ptr impl_; +}; +} // namespace gazebo_plugins + +#endif // GAZEBO_PLUGINS__GAZEBO_ROS_ACKERMANN_DRIVE_HPP_ diff --git a/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp b/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp new file mode 100644 index 000000000..99e8cbcc0 --- /dev/null +++ b/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp @@ -0,0 +1,596 @@ +// Copyright 2019 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +namespace gazebo_plugins +{ +class GazeboRosAckermannDrivePrivate +{ +public: + /// Indicates which joint + enum + { + /// Front right wheel + FRONT_RIGHT, + + /// Front left wheel + FRONT_LEFT, + + /// Rear right wheel + REAR_RIGHT, + + /// Rear left wheel + REAR_LEFT, + + /// Right steering + STEER_RIGHT, + + /// Left steering + STEER_LEFT, + + /// Steering wheel + STEER_WHEEL + }; + + /// Callback to be called at every simulation iteration. + /// \param[in] _info Updated simulation info. + void OnUpdate(const gazebo::common::UpdateInfo & _info); + + /// Callback when a velocity command is received. + /// \param[in] _msg Twist command message. + void OnCmdVel(geometry_msgs::msg::Twist::SharedPtr _msg); + + /// Extracts radius of a cylinder or sphere collision shape + /// \param[in] _coll Pointer to collision + /// \return If the collision shape is valid, return radius + /// \return If the collision shape is invalid, return 0 + double CollisionRadius(const gazebo::physics::CollisionPtr & _coll); + + /// Update odometry according to world + void UpdateOdometryWorld(); + + /// Publish odometry transforms + /// \param[in] _current_time Current simulation time + void PublishOdometryTf(const gazebo::common::Time & _current_time); + + /// Publish trasforms for the wheels + /// \param[in] _current_time Current simulation time + void PublishWheelsTf(const gazebo::common::Time & _current_time); + + /// Publish odometry messages + /// \param[in] _current_time Current simulation time + void PublishOdometryMsg(const gazebo::common::Time & _current_time); + + /// A pointer to the GazeboROS node. + gazebo_ros::Node::SharedPtr ros_node_; + + /// Subscriber to command velocities + rclcpp::Subscription::SharedPtr cmd_vel_sub_; + + /// Odometry publisher + rclcpp::Publisher::SharedPtr odometry_pub_; + + /// Distance publisher + rclcpp::Publisher::SharedPtr distance_pub_; + + /// Connection to event called at every world iteration. + gazebo::event::ConnectionPtr update_connection_; + + /// Pointers to wheel joints. + std::vector joints_; + + /// Pointer to model. + gazebo::physics::ModelPtr model_; + + /// Distance between the wheels, in meters. + double wheel_separation_; + + /// Distance between front and rear axles, in meters. + double wheel_base_; + + /// Radius of rear wheels, in meters. + double wheel_radius_; + + /// Angle ratio between the steering wheel and the front wheels + double steering_ratio_ = 0; + + // Max steering angle + double max_speed_ = 0; + + // Max steering angle of tyre + double max_steer_ = 0; + + /// To broadcast TFs + std::shared_ptr transform_broadcaster_; + + /// Protect variables accessed on callbacks. + std::mutex lock_; + + /// Linear velocity in X received on command (m/s). + double target_linear_{0.0}; + + /// Angular velocity in Z received on command (rad/s). + double target_rot_{0.0}; + + /// Update period in seconds. + double update_period_; + + /// Last update time. + gazebo::common::Time last_update_time_; + + /// Odometry frame ID + std::string odometry_frame_; + + /// Keep latest odometry message + nav_msgs::msg::Odometry odom_; + + /// Keep latest distance message + std_msgs::msg::Float32 distance_; + + /// Robot base frame ID + std::string robot_base_frame_; + + /// True to publish odometry messages. + bool publish_odom_; + + /// True to publish distance travelled + bool publish_distance_; + + /// True to publish wheel-to-base transforms. + bool publish_wheel_tf_; + + /// True to publish odom-to-world transforms. + bool publish_odom_tf_; + + /// Covariance in odometry + double covariance_[3]; + + /// PID control for left steering control + gazebo::common::PID pid_left_steering_; + + /// PID control for right steering control + gazebo::common::PID pid_right_steering_; + + /// PID control for linear velocity control + gazebo::common::PID pid_linear_vel_; +}; + +GazeboRosAckermannDrive::GazeboRosAckermannDrive() +: impl_(std::make_unique()) +{ +} + +GazeboRosAckermannDrive::~GazeboRosAckermannDrive() +{ +} + +void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + impl_->model_ = _model; + + auto world = impl_->model_->GetWorld(); + auto physicsEngine = world->Physics(); + physicsEngine->SetParam("friction_model", std::string("cone_model")); + + // Initialize ROS node + impl_->ros_node_ = gazebo_ros::Node::Get(_sdf); + + impl_->joints_.resize(7); + + auto steering_wheel_joint = + _sdf->Get("steering_wheel_joint", "steering_wheel_joint").first; + impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_WHEEL] = + _model->GetJoint(steering_wheel_joint); + if (!impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_WHEEL]) { + RCLCPP_WARN(impl_->ros_node_->get_logger(), + "Steering wheel joint [%s] not found.", steering_wheel_joint.c_str()); + impl_->joints_.resize(6); + } + + auto front_right_joint = _sdf->Get("front_right_joint", "front_right_joint").first; + impl_->joints_[GazeboRosAckermannDrivePrivate::FRONT_RIGHT] = _model->GetJoint(front_right_joint); + if (!impl_->joints_[GazeboRosAckermannDrivePrivate::FRONT_RIGHT]) { + RCLCPP_ERROR(impl_->ros_node_->get_logger(), + "Front right wheel joint [%s] not found, plugin will not work.", front_right_joint.c_str()); + impl_->ros_node_.reset(); + return; + } + + auto front_left_joint = _sdf->Get("front_left_joint", "front_left_joint").first; + impl_->joints_[GazeboRosAckermannDrivePrivate::FRONT_LEFT] = _model->GetJoint(front_left_joint); + if (!impl_->joints_[GazeboRosAckermannDrivePrivate::FRONT_LEFT]) { + RCLCPP_ERROR(impl_->ros_node_->get_logger(), + "Front left wheel joint [%s] not found, plugin will not work.", front_left_joint.c_str()); + impl_->ros_node_.reset(); + return; + } + + auto rear_right_joint = _sdf->Get("rear_right_joint", "rear_right_joint").first; + impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_RIGHT] = _model->GetJoint(rear_right_joint); + if (!impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_RIGHT]) { + RCLCPP_ERROR(impl_->ros_node_->get_logger(), + "Rear right wheel joint [%s] not found, plugin will not work.", rear_right_joint.c_str()); + impl_->ros_node_.reset(); + return; + } + + auto rear_left_joint = _sdf->Get("rear_left_joint", "rear_left_joint").first; + impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_LEFT] = _model->GetJoint(rear_left_joint); + if (!impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_LEFT]) { + RCLCPP_ERROR(impl_->ros_node_->get_logger(), + "Rear left wheel joint [%s] not found, plugin will not work.", rear_left_joint.c_str()); + impl_->ros_node_.reset(); + return; + } + + auto right_steering_joint = + _sdf->Get("right_steering_joint", "right_steering_joint").first; + impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_RIGHT] = + _model->GetJoint(right_steering_joint); + if (!impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_RIGHT]) { + RCLCPP_ERROR(impl_->ros_node_->get_logger(), + "Right wheel steering joint [%s] not found, plugin will not work.", + right_steering_joint.c_str()); + impl_->ros_node_.reset(); + return; + } + + auto left_steering_joint = + _sdf->Get("left_steering_joint", "left_steering_joint").first; + impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_LEFT] = + _model->GetJoint(left_steering_joint); + if (!impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_LEFT]) { + RCLCPP_ERROR(impl_->ros_node_->get_logger(), + "Left wheel steering joint [%s] not found, plugin will not work.", + left_steering_joint.c_str()); + impl_->ros_node_.reset(); + return; + } + + impl_->max_speed_ = _sdf->Get("max_speed", 20.0).first; + impl_->max_steer_ = _sdf->Get("max_steer", 0.6).first; + + // Max the steering wheel can rotate + auto max_steering_angle = _sdf->Get("max_steering_angle", 7.85).first; + + // Compute the angle ratio between the steering wheel and the tires + impl_->steering_ratio_ = impl_->max_steer_ / max_steering_angle; + + auto pid = _sdf->Get( + "right_steering_pid_gain", ignition::math::Vector3d::Zero).first; + auto i_range = _sdf->Get( + "right_steering_i_range", ignition::math::Vector2d::Zero).first; + impl_->pid_right_steering_.Init(pid.X(), pid.Y(), pid.Z(), i_range.Y(), i_range.X()); + + pid = _sdf->Get( + "left_steering_pid_gain", ignition::math::Vector3d::Zero).first; + i_range = _sdf->Get( + "left_steering_i_range", ignition::math::Vector2d::Zero).first; + impl_->pid_left_steering_.Init(pid.X(), pid.Y(), pid.Z(), i_range.Y(), i_range.X()); + + pid = _sdf->Get( + "linear_velocity_pid_gain", ignition::math::Vector3d::Zero).first; + i_range = _sdf->Get( + "linear_velocity_i_range", ignition::math::Vector2d::Zero).first; + impl_->pid_linear_vel_.Init(pid.X(), pid.Y(), pid.Z(), i_range.Y(), i_range.X()); + + // Update wheel radiu for wheel from SDF collision objects + // assumes that wheel link is child of joint (and not parent of joint) + // assumes that wheel link has only one collision + // assumes all wheel of both rear wheels of same radii + unsigned int id = 0; + impl_->wheel_radius_ = impl_->CollisionRadius( + impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_RIGHT]->GetChild()->GetCollision(id)); + + // Compute wheel_base, front wheel separation, and rear wheel separation + // first compute the positions of the 4 wheel centers + // again assumes wheel link is child of joint and has only one collision + auto front_right_center_pos = impl_->joints_[GazeboRosAckermannDrivePrivate::FRONT_RIGHT]-> + GetChild()->GetCollision(id)->WorldPose().Pos(); + auto front_left_center_pos = impl_->joints_[GazeboRosAckermannDrivePrivate::FRONT_LEFT]-> + GetChild()->GetCollision(id)->WorldPose().Pos(); + auto rear_right_center_pos = impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_RIGHT]-> + GetChild()->GetCollision(id)->WorldPose().Pos(); + auto rear_left_center_pos = impl_->joints_[GazeboRosAckermannDrivePrivate::REAR_LEFT]-> + GetChild()->GetCollision(id)->WorldPose().Pos(); + + auto distance = front_left_center_pos - front_right_center_pos; + impl_->wheel_separation_ = distance.Length(); + + // to compute wheelbase, first position of axle centers are computed + auto front_axle_pos = (front_left_center_pos + front_right_center_pos) / 2; + auto rear_axle_pos = (rear_left_center_pos + rear_right_center_pos) / 2; + // then the wheelbase is the distance between the axle centers + distance = front_axle_pos - rear_axle_pos; + impl_->wheel_base_ = distance.Length(); + + // Update rate + auto update_rate = _sdf->Get("update_rate", 100.0).first; + if (update_rate > 0.0) { + impl_->update_period_ = 1.0 / update_rate; + } else { + impl_->update_period_ = 0.0; + } + impl_->last_update_time_ = _model->GetWorld()->SimTime(); + + impl_->cmd_vel_sub_ = impl_->ros_node_->create_subscription( + "cmd_vel", rclcpp::QoS(rclcpp::KeepLast(1)), + std::bind(&GazeboRosAckermannDrivePrivate::OnCmdVel, impl_.get(), std::placeholders::_1)); + + RCLCPP_INFO(impl_->ros_node_->get_logger(), + "Subscribed to [%s]", impl_->cmd_vel_sub_->get_topic_name()); + + // Odometry + impl_->odometry_frame_ = _sdf->Get("odometry_frame", "odom").first; + impl_->robot_base_frame_ = _sdf->Get("robot_base_frame", "base_footprint").first; + + // Advertise odometry topic + impl_->publish_odom_ = _sdf->Get("publish_odom", false).first; + if (impl_->publish_odom_) { + impl_->odometry_pub_ = impl_->ros_node_->create_publisher( + "odom", rclcpp::QoS(rclcpp::KeepLast(1))); + + RCLCPP_INFO(impl_->ros_node_->get_logger(), "Advertise odometry on [%s]", + impl_->odometry_pub_->get_topic_name()); + } + + // Advertise distance travelled + impl_->publish_distance_ = _sdf->Get("publish_distance", false).first; + if (impl_->publish_distance_) { + impl_->distance_pub_ = impl_->ros_node_->create_publisher( + "distance", rclcpp::QoS(rclcpp::KeepLast(1))); + + RCLCPP_INFO(impl_->ros_node_->get_logger(), "Advertise distance on [%s]", + impl_->distance_pub_->get_topic_name()); + } + + // Create TF broadcaster if needed + impl_->publish_wheel_tf_ = _sdf->Get("publish_wheel_tf", false).first; + impl_->publish_odom_tf_ = _sdf->Get("publish_odom_tf", false).first; + if (impl_->publish_wheel_tf_ || impl_->publish_odom_tf_) { + impl_->transform_broadcaster_ = + std::make_shared(impl_->ros_node_); + + if (impl_->publish_odom_tf_) { + RCLCPP_INFO(impl_->ros_node_->get_logger(), + "Publishing odom transforms between [%s] and [%s]", impl_->odometry_frame_.c_str(), + impl_->robot_base_frame_.c_str()); + } + + if (impl_->publish_wheel_tf_) { + for (auto & joint : impl_->joints_) { + RCLCPP_INFO(impl_->ros_node_->get_logger(), + "Publishing wheel transforms between [%s], [%s] and [%s]", + impl_->robot_base_frame_.c_str(), joint->GetName().c_str(), joint->GetName().c_str()); + } + } + } + + auto pose = impl_->model_->WorldPose(); + impl_->odom_.pose.pose.position = gazebo_ros::Convert(pose.Pos()); + impl_->odom_.pose.pose.orientation = gazebo_ros::Convert( + pose.Rot()); + + impl_->covariance_[0] = _sdf->Get("covariance_x", 0.00001).first; + impl_->covariance_[1] = _sdf->Get("covariance_y", 0.00001).first; + impl_->covariance_[2] = _sdf->Get("covariance_yaw", 0.001).first; + + // Listen to the update event (broadcast every simulation iteration) + impl_->update_connection_ = gazebo::event::Events::ConnectWorldUpdateBegin( + std::bind(&GazeboRosAckermannDrivePrivate::OnUpdate, impl_.get(), std::placeholders::_1)); +} + +void GazeboRosAckermannDrive::Reset() +{ + impl_->last_update_time_ = impl_->model_->GetWorld()->SimTime(); + + impl_->target_linear_ = 0; + impl_->target_rot_ = 0; + impl_->distance_.data = 0; +} + +void GazeboRosAckermannDrivePrivate::OnUpdate(const gazebo::common::UpdateInfo & _info) +{ + std::lock_guard lock(lock_); + + double seconds_since_last_update = (_info.simTime - last_update_time_).Double(); + + // Update odom + UpdateOdometryWorld(); + + if (seconds_since_last_update < update_period_) { + return; + } + + if (publish_distance_) { + distance_pub_->publish(distance_); + } + + if (publish_odom_) { + PublishOdometryMsg(_info.simTime); + } + + if (publish_wheel_tf_) { + PublishWheelsTf(_info.simTime); + } + + if (publish_odom_tf_) { + PublishOdometryTf(_info.simTime); + } + + // Current speed assuming equal for left rear and right rear + auto linear_vel = joints_[REAR_RIGHT]->GetVelocity(0); + auto target_linear = ignition::math::clamp(target_linear_, -max_speed_, max_speed_); + double linear_diff = linear_vel - target_linear / wheel_radius_; + double linear_cmd = pid_linear_vel_.Update(linear_diff, seconds_since_last_update); + + auto target_rot = target_rot_ * copysign(1.0, target_linear_); + target_rot = ignition::math::clamp(target_rot, -max_steer_, max_steer_); + + double tanSteer = tan(target_rot); + + auto target_left_steering = + atan2(tanSteer, 1.0 - wheel_separation_ / 2.0 / wheel_base_ * tanSteer); + auto target_right_steering = + atan2(tanSteer, 1.0 + wheel_separation_ / 2.0 / wheel_base_ * tanSteer); + + auto left_steering_angle = joints_[STEER_LEFT]->Position(0); + auto right_steering_angle = joints_[STEER_RIGHT]->Position(0); + + double left_steering_diff = left_steering_angle - target_left_steering; + double left_steering_cmd = + pid_left_steering_.Update(left_steering_diff, seconds_since_last_update); + + double right_steering_diff = right_steering_angle - target_right_steering; + double right_steering_cmd = + pid_right_steering_.Update(right_steering_diff, seconds_since_last_update); + + auto steer_wheel_angle = (left_steering_angle + right_steering_angle) * 0.5 / steering_ratio_; + + joints_[STEER_LEFT]->SetForce(0, left_steering_cmd); + joints_[STEER_RIGHT]->SetForce(0, right_steering_cmd); + joints_[REAR_RIGHT]->SetForce(0, linear_cmd); + joints_[REAR_LEFT]->SetForce(0, linear_cmd); + + if (joints_.size() == 7) { + joints_[STEER_WHEEL]->SetPosition(0, steer_wheel_angle); + } + + last_update_time_ = _info.simTime; +} + +void GazeboRosAckermannDrivePrivate::OnCmdVel(const geometry_msgs::msg::Twist::SharedPtr _msg) +{ + std::lock_guard scoped_lock(lock_); + target_linear_ = _msg->linear.x; + target_rot_ = _msg->angular.z; +} + +double GazeboRosAckermannDrivePrivate::CollisionRadius(const gazebo::physics::CollisionPtr & _coll) +{ + if (!_coll || !(_coll->GetShape())) { + return 0; + } + if (_coll->GetShape()->HasType(gazebo::physics::Base::CYLINDER_SHAPE)) { + gazebo::physics::CylinderShape * cyl = + dynamic_cast(_coll->GetShape().get()); + return cyl->GetRadius(); + } else if (_coll->GetShape()->HasType(gazebo::physics::Base::SPHERE_SHAPE)) { + gazebo::physics::SphereShape * sph = + dynamic_cast(_coll->GetShape().get()); + return sph->GetRadius(); + } + return 0; +} + +void GazeboRosAckermannDrivePrivate::UpdateOdometryWorld() +{ + auto prev_x = odom_.pose.pose.position.x; + auto prev_y = odom_.pose.pose.position.y; + + auto pose = model_->WorldPose(); + odom_.pose.pose.position = gazebo_ros::Convert(pose.Pos()); + odom_.pose.pose.orientation = gazebo_ros::Convert(pose.Rot()); + + distance_.data += hypot(prev_x - odom_.pose.pose.position.x, prev_y - odom_.pose.pose.position.y); + + // Get velocity in odom frame + auto linear = model_->WorldLinearVel(); + odom_.twist.twist.angular.z = model_->WorldAngularVel().Z(); + + // Convert velocity to child_frame_id(aka base_footprint) + auto yaw = static_cast(pose.Rot().Yaw()); + odom_.twist.twist.linear.x = cosf(yaw) * linear.X() + sinf(yaw) * linear.Y(); + odom_.twist.twist.linear.y = cosf(yaw) * linear.Y() - sinf(yaw) * linear.X(); +} + +void GazeboRosAckermannDrivePrivate::PublishOdometryTf(const gazebo::common::Time & _current_time) +{ + geometry_msgs::msg::TransformStamped msg; + msg.header.stamp = gazebo_ros::Convert(_current_time); + msg.header.frame_id = odometry_frame_; + msg.child_frame_id = robot_base_frame_; + msg.transform.translation = + gazebo_ros::Convert(odom_.pose.pose.position); + msg.transform.rotation = odom_.pose.pose.orientation; + + transform_broadcaster_->sendTransform(msg); +} + +void GazeboRosAckermannDrivePrivate::PublishWheelsTf(const gazebo::common::Time & _current_time) +{ + for (const auto & joint : joints_) { + auto pose = joint->GetChild()->WorldPose() - model_->WorldPose(); + + geometry_msgs::msg::TransformStamped msg; + msg.header.stamp = gazebo_ros::Convert(_current_time); + msg.header.frame_id = robot_base_frame_; + msg.child_frame_id = joint->GetChild()->GetName(); + msg.transform.translation = gazebo_ros::Convert(pose.Pos()); + msg.transform.rotation = gazebo_ros::Convert(pose.Rot()); + + transform_broadcaster_->sendTransform(msg); + } +} + +void GazeboRosAckermannDrivePrivate::PublishOdometryMsg(const gazebo::common::Time & _current_time) +{ + // Set covariance + odom_.pose.covariance[0] = covariance_[0]; + odom_.pose.covariance[7] = covariance_[1]; + odom_.pose.covariance[14] = 1000000000000.0; + odom_.pose.covariance[21] = 1000000000000.0; + odom_.pose.covariance[28] = 1000000000000.0; + odom_.pose.covariance[35] = covariance_[2]; + + odom_.twist.covariance[0] = covariance_[0]; + odom_.twist.covariance[7] = covariance_[1]; + odom_.twist.covariance[14] = 1000000000000.0; + odom_.twist.covariance[21] = 1000000000000.0; + odom_.twist.covariance[28] = 1000000000000.0; + odom_.twist.covariance[35] = covariance_[2]; + + // Set header + odom_.header.frame_id = odometry_frame_; + odom_.child_frame_id = robot_base_frame_; + odom_.header.stamp = gazebo_ros::Convert(_current_time); + + // Publish + odometry_pub_->publish(odom_); +} +GZ_REGISTER_MODEL_PLUGIN(GazeboRosAckermannDrive) +} // namespace gazebo_plugins diff --git a/gazebo_plugins/test/CMakeLists.txt b/gazebo_plugins/test/CMakeLists.txt index ab54dd2c4..b6eadb0b1 100644 --- a/gazebo_plugins/test/CMakeLists.txt +++ b/gazebo_plugins/test/CMakeLists.txt @@ -12,6 +12,7 @@ endforeach() # Tests set(tests + test_gazebo_ros_ackermann_drive test_gazebo_ros_diff_drive test_gazebo_ros_elevator test_gazebo_ros_force diff --git a/gazebo_plugins/test/test_gazebo_ros_ackermann_drive.cpp b/gazebo_plugins/test/test_gazebo_ros_ackermann_drive.cpp new file mode 100644 index 000000000..3aae7ec1b --- /dev/null +++ b/gazebo_plugins/test/test_gazebo_ros_ackermann_drive.cpp @@ -0,0 +1,120 @@ +// Copyright 2019 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include + +#include + +#define tol 10e-1 + +using namespace std::literals::chrono_literals; // NOLINT + +class GazeboRosAckermannDriveTest : public gazebo::ServerFixture +{ +}; + +TEST_F(GazeboRosAckermannDriveTest, Publishing) +{ + // Load test world and start paused + this->Load("worlds/gazebo_ros_ackermann_drive.world", true); + + // World + auto world = gazebo::physics::get_world(); + ASSERT_NE(nullptr, world); + + // Model + auto vehicle = world->ModelByName("vehicle"); + ASSERT_NE(nullptr, vehicle); + + // Create node and executor + auto node = std::make_shared("gazebo_ros_ackermann_drive_test"); + ASSERT_NE(nullptr, node); + + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + + // Create subscriber + nav_msgs::msg::Odometry::SharedPtr latestMsg; + auto sub = node->create_subscription( + "test/odom_test", rclcpp::QoS(rclcpp::KeepLast(1)), + [&latestMsg](const nav_msgs::msg::Odometry::SharedPtr _msg) { + latestMsg = _msg; + }); + + // Step a bit for model to settle + world->Step(100); + executor.spin_once(100ms); + + // Check model state + EXPECT_NEAR(0.0, vehicle->WorldPose().Pos().X(), tol); + EXPECT_NEAR(0.0, vehicle->WorldPose().Pos().Y(), tol); + EXPECT_NEAR(0.0, vehicle->WorldPose().Rot().Yaw(), tol); + EXPECT_NEAR(0.0, vehicle->WorldLinearVel().X(), tol); + EXPECT_NEAR(0.0, vehicle->WorldAngularVel().Z(), tol); + + // Send command + auto pub = node->create_publisher( + "test/cmd_test", rclcpp::QoS(rclcpp::KeepLast(1))); + + auto msg = geometry_msgs::msg::Twist(); + msg.linear.x = 5.0; + msg.angular.z = 0.1; + pub->publish(msg); + + // Wait for it to be processed + int sleep{0}; + int maxSleep{300}; + + double yaw = static_cast(vehicle->WorldPose().Rot().Yaw()); + auto linear_vel = vehicle->WorldLinearVel(); + double linear_vel_x = cosf(yaw) * linear_vel.X() + sinf(yaw) * linear_vel.Y(); + + for (; sleep < maxSleep && (linear_vel_x < 4.0 || + vehicle->WorldAngularVel().Z() < 0.0); ++sleep) + { + yaw = static_cast(vehicle->WorldPose().Rot().Yaw()); + linear_vel = vehicle->WorldLinearVel(); + linear_vel_x = cosf(yaw) * linear_vel.X() + sinf(yaw) * linear_vel.Y(); + world->Step(100); + executor.spin_once(100ms); + gazebo::common::Time::MSleep(100); + } + EXPECT_NE(sleep, maxSleep); + + // Check message + ASSERT_NE(nullptr, latestMsg); + EXPECT_EQ("odom_test", latestMsg->header.frame_id); + EXPECT_LT(0.0, latestMsg->pose.pose.position.x); + EXPECT_LT(0.0, latestMsg->pose.pose.orientation.z); + + // Check movement + yaw = static_cast(vehicle->WorldPose().Rot().Yaw()); + linear_vel = vehicle->WorldLinearVel(); + linear_vel_x = cosf(yaw) * linear_vel.X() + sinf(yaw) * linear_vel.Y(); + EXPECT_LT(0.0, vehicle->WorldPose().Pos().X()); + EXPECT_LT(0.0, yaw); + EXPECT_NEAR(5.0, linear_vel_x, tol); + EXPECT_NEAR(0.1, vehicle->WorldAngularVel().Z(), tol); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/gazebo_plugins/test/worlds/gazebo_ros_ackermann_drive.world b/gazebo_plugins/test/worlds/gazebo_ros_ackermann_drive.world new file mode 100644 index 000000000..f39d81bfd --- /dev/null +++ b/gazebo_plugins/test/worlds/gazebo_ros_ackermann_drive.world @@ -0,0 +1,587 @@ + + + + + model://ground_plane + + + + 0 0 0.03 0 0 0 + + 0 0 0 0 0 1.57 + + 1326.0 + 0 -0.266 0.48 0 0 0 + + 2581.13354740 + 0.0 + 591.30846112 + 0.0 + 0.0 + 2681.95008628 + + + + + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Hybrid +
false
+
+
+
+
+ + + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Hybrid_Interior +
false
+
+
+
+
+ + + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Hybrid_Windows +
false
+
+
+
+
+ + + 0.0 0.05 0.625 0 0 0 + + + 1.7526 2.1 0.95 + + + + + + 0.0 -2.0 0.458488 0.0 0 0 + + + 1.337282 0.48 0.566691 + + + + + + 0.0 -1.900842 0.676305 0.341247 0 0 + + + 1.597968 0.493107 0.265468 + + + + + + 0.0 -0.875105 1.032268 0.335476 0 0 + + + 1.168381 1.654253 0.272347 + + + + + + 0.0 0.161236 1.386042 0.135030 0 0 + + + 1.279154 0.625988 0.171868 + + + + + + 0.0 0.817696 1.360069 -0.068997 0 0 + + + 1.285130 0.771189 0.226557 + + + + + + 0.0 1.640531 1.175126 -0.262017 0 0 + + + 1.267845 1.116344 0.244286 + + + + + + 0.0 1.637059 0.888180 0.0 0 0 + + + 1.788064 1.138988 0.482746 + + + + + + 0.0 2.054454 0.577870 0.0 0 0 + + + 1.781650 0.512093 0.581427 + + + + + + + 0.627868 0.357734 0.988243 -1.302101 0 1.57 + + 1.0 + + 0.14583300 + 0 + 0 + 0.14583300 + 0 + 0.12500000 + + + + + + 0.178172 + 0.041845 + + + + + + 0.003 + + + + + + 0 0 0 1.302101 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Steering_Wheel +
true
+
+
+
+
+ + + + 1.41 0.76 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + + 0.04 0.0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Left_ +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 0.9 + 0.9 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + + 1.41 -0.76 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + -0.04 0.0 0.0 0 0 0 + 0 0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Right +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 0.9 + 0.9 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + + + -1.45 0.786 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + + 0.04 0.0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Left_ +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 1.1 + 1.1 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + + -1.45 -0.786 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + -0.04 0.0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Right +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 1.1 + 1.1 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + 0 0 0 -0.08726646259971647 0 0 + front_left_wheel + chassis + + 0 0 1 + + + -0.8727 + 0.8727 + + + + 1 0 0 + + 18.0474092253 + + + + + + 0 0 0 -0.08726646259971647 0 0 + front_right_wheel + chassis + + 0 0 1 + + + -0.8727 + 0.8727 + + + + 1 0 0 + + 18.0474092253 + + + + + + -1.45 0 0.3 0 0 0 + + 30.0 + + 0.08437499999999999 + 0.0 + 4.64581 + 0.0 + 0.0 + 4.64581 + + + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 1.357 + 0.075 + + + + + + + + + + rear_axle + chassis + + 0 1 0 + + -0.05089058524173028 + 0.05089058524173028 + + + 20000.0 + 2000.0 + + + + + rear_left_wheel + rear_axle + + 1 0 0 + + 12.031606150200002 + + + + + rear_right_wheel + rear_axle + + 1 0 0 + + 12.031606150200002 + + + + + + -0.002 0 0 0 0 0 + chassis + steering_wheel + + -0.964118 0.000768 0.265556 + + -7.85 + 7.85 + + + 1.0 + + true + + + + 1 + + + + + + + + test + cmd_vel:=cmd_test + odom:=odom_test + distance:=distance_test + + + 100.0 + + + front_left_combined_joint + front_right_combined_joint + rear_left_wheel_joint + rear_right_wheel_joint + front_left_combined_joint + front_right_combined_joint + steering_joint + + + + 0.6458 + + + 7.85 + + + 20 + + + 1500 0 1 + 0 0 + 1500 0 1 + 0 0 + 1000 0 1 + 0 0 + + + true + true + true + true + + odom_test + chassis + + +
+ +
+
diff --git a/gazebo_plugins/worlds/gazebo_ros_ackermann_drive_demo.world b/gazebo_plugins/worlds/gazebo_ros_ackermann_drive_demo.world new file mode 100644 index 000000000..42d06a033 --- /dev/null +++ b/gazebo_plugins/worlds/gazebo_ros_ackermann_drive_demo.world @@ -0,0 +1,612 @@ + + + + + + model://sun + + + + model://ground_plane + + + + 0 0 0.03 0 0 0 + + 0 0 0 0 0 1.57 + + 1326.0 + 0 -0.266 0.48 0 0 0 + + 2581.13354740 + 0.0 + 591.30846112 + 0.0 + 0.0 + 2681.95008628 + + + + + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Hybrid +
false
+
+
+
+
+ + + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Hybrid_Interior +
false
+
+
+
+
+ + + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Hybrid_Windows +
false
+
+
+
+
+ + + 0.0 0.05 0.625 0 0 0 + + + 1.7526 2.1 0.95 + + + + + + 0.0 -2.0 0.458488 0.0 0 0 + + + 1.337282 0.48 0.566691 + + + + + + 0.0 -1.900842 0.676305 0.341247 0 0 + + + 1.597968 0.493107 0.265468 + + + + + + 0.0 -0.875105 1.032268 0.335476 0 0 + + + 1.168381 1.654253 0.272347 + + + + + + 0.0 0.161236 1.386042 0.135030 0 0 + + + 1.279154 0.625988 0.171868 + + + + + + 0.0 0.817696 1.360069 -0.068997 0 0 + + + 1.285130 0.771189 0.226557 + + + + + + 0.0 1.640531 1.175126 -0.262017 0 0 + + + 1.267845 1.116344 0.244286 + + + + + + 0.0 1.637059 0.888180 0.0 0 0 + + + 1.788064 1.138988 0.482746 + + + + + + 0.0 2.054454 0.577870 0.0 0 0 + + + 1.781650 0.512093 0.581427 + + + + + + + 0.627868 0.357734 0.988243 -1.302101 0 1.57 + + 1.0 + + 0.14583300 + 0 + 0 + 0.14583300 + 0 + 0.12500000 + + + + + + 0.178172 + 0.041845 + + + + + + 0.003 + + + + + + 0 0 0 1.302101 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Steering_Wheel +
true
+
+
+
+
+ + + + 1.41 0.76 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + + 0.04 0.0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Left_ +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 0.9 + 0.9 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + + 1.41 -0.76 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + -0.04 0.0 0.0 0 0 0 + 0 0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Right +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 0.9 + 0.9 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + + + -1.45 0.786 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + + 0.04 0.0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Left_ +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 1.1 + 1.1 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + + -1.45 -0.786 0.3 0 0 1.57 + + 11 + + 0.58631238 + 0.0 + 0.33552910 + 0.0 + 0.0 + 0.33552910 + + + + -0.04 0.0 0.0 0 0 0 + + + model://prius_hybrid/meshes/Hybrid.obj + 0.01 0.01 0.01 + + Wheel_Front_Right +
true
+
+
+
+
+ + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 0.31265 + + + + + + 1.1 + 1.1 + 0.0 + 0.0 + + + + + 0.001 + 1e9 + + + + + + + + 0 0 0 -0.08726646259971647 0 0 + front_left_wheel + chassis + + 0 0 1 + + + -0.8727 + 0.8727 + + + + 1 0 0 + + 18.0474092253 + + + + + + 0 0 0 -0.08726646259971647 0 0 + front_right_wheel + chassis + + 0 0 1 + + + -0.8727 + 0.8727 + + + + 1 0 0 + + 18.0474092253 + + + + + + -1.45 0 0.3 0 0 0 + + 30.0 + + 0.08437499999999999 + 0.0 + 4.64581 + 0.0 + 0.0 + 4.64581 + + + + 0.0 0.0 0.0 0 1.5707963267948966 0 + + + 1.357 + 0.075 + + + + + + + + + + rear_axle + chassis + + 0 1 0 + + -0.05089058524173028 + 0.05089058524173028 + + + 20000.0 + 2000.0 + + + + + rear_left_wheel + rear_axle + + 1 0 0 + + 12.031606150200002 + + + + + rear_right_wheel + rear_axle + + 1 0 0 + + 12.031606150200002 + + + + + + -0.002 0 0 0 0 0 + chassis + steering_wheel + + -0.964118 0.000768 0.265556 + + -7.85 + 7.85 + + + 1.0 + + true + + + + 1 + + + + + + + + demo + cmd_vel:=cmd_demo + odom:=odom_demo + distance:=distance_demo + + + 100.0 + + + front_left_combined_joint + front_right_combined_joint + rear_left_wheel_joint + rear_right_wheel_joint + front_left_combined_joint + front_right_combined_joint + steering_joint + + + + 0.6458 + + + 7.85 + + + 20 + + + 1500 0 1 + 0 0 + 1500 0 1 + 0 0 + 1000 0 1 + 0 0 + + + true + true + true + true + + odom_demo + chassis + + +
+ +
+