diff --git a/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp b/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp index 99e8cbcc0..16d42d875 100644 --- a/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp +++ b/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp @@ -216,7 +216,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_WHEEL] = _model->GetJoint(steering_wheel_joint); if (!impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_WHEEL]) { - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "Steering wheel joint [%s] not found.", steering_wheel_joint.c_str()); impl_->joints_.resize(6); } @@ -224,7 +225,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen 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(), + 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; @@ -233,7 +235,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen 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(), + 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; @@ -242,7 +245,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen 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(), + 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; @@ -251,7 +255,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen 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(), + 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; @@ -262,7 +267,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_RIGHT] = _model->GetJoint(right_steering_joint); if (!impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_RIGHT]) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + 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(); @@ -274,7 +280,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_LEFT] = _model->GetJoint(left_steering_joint); if (!impl_->joints_[GazeboRosAckermannDrivePrivate::STEER_LEFT]) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + 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(); @@ -351,8 +358,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen "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()); + 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; @@ -364,7 +371,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen 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]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise odometry on [%s]", impl_->odometry_pub_->get_topic_name()); } @@ -374,7 +382,8 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen 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]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise distance on [%s]", impl_->distance_pub_->get_topic_name()); } @@ -386,14 +395,16 @@ void GazeboRosAckermannDrive::Load(gazebo::physics::ModelPtr _model, sdf::Elemen std::make_shared(impl_->ros_node_); if (impl_->publish_odom_tf_) { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + 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(), + 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()); } diff --git a/gazebo_plugins/src/gazebo_ros_bumper.cpp b/gazebo_plugins/src/gazebo_ros_bumper.cpp index 50ef37a91..8e29be098 100644 --- a/gazebo_plugins/src/gazebo_ros_bumper.cpp +++ b/gazebo_plugins/src/gazebo_ros_bumper.cpp @@ -73,7 +73,8 @@ void GazeboRosBumper::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ impl_->parent_sensor_ = std::dynamic_pointer_cast(_sensor); if (!impl_->parent_sensor_) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Contact sensor parent is not of type ContactSensor. Aborting"); impl_->ros_node_.reset(); return; @@ -83,7 +84,8 @@ void GazeboRosBumper::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ impl_->pub_ = impl_->ros_node_->create_publisher( "bumper_states", rclcpp::SensorDataQoS()); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing contact states to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing contact states to [%s]", impl_->pub_->get_topic_name()); // Get tf frame for output diff --git a/gazebo_plugins/src/gazebo_ros_camera.cpp b/gazebo_plugins/src/gazebo_ros_camera.cpp index feb480d41..5711625a5 100644 --- a/gazebo_plugins/src/gazebo_ros_camera.cpp +++ b/gazebo_plugins/src/gazebo_ros_camera.cpp @@ -158,7 +158,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ impl_->sensor_type_ = GazeboRosCameraPrivate::CAMERA; gazebo::CameraPlugin::Load(_sensor, _sdf); } else { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Plugin must be attached to sensor of type `camera`, `depth` or `multicamera`"); impl_->ros_node_.reset(); return; @@ -173,13 +174,14 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ if (impl_->sensor_type_ != GazeboRosCameraPrivate::MULTICAMERA) { // Image publisher // TODO(louise) Migrate image_connect logic once SubscriberStatusCallback is ported to ROS2 - impl_->image_pub_.push_back(image_transport::create_publisher(impl_->ros_node_.get(), - impl_->camera_name_ + "/image_raw")); + impl_->image_pub_.push_back( + image_transport::create_publisher( + impl_->ros_node_.get(), impl_->camera_name_ + "/image_raw")); // TODO(louise) Uncomment this once image_transport::Publisher has a function to return the // full topic. - // RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing images to [%s]", - // impl_->image_pub_.getTopic()); + // RCLCPP_INFO( + // impl_->ros_node_->get_logger(), "Publishing images to [%s]", impl_->image_pub_.getTopic()); // Camera info publisher // TODO(louise) Migrate ImageConnect logic once SubscriberStatusCallback is ported to ROS2 @@ -188,16 +190,20 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ impl_->camera_name_ + "/camera_info", rclcpp::SensorDataQoS())); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing camera info to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing camera info to [%s]", impl_->camera_info_pub_.back()->get_topic_name()); } else { for (uint64_t i = 0; i < impl_->num_cameras_; ++i) { // Image publisher - impl_->image_pub_.push_back(image_transport::create_publisher(impl_->ros_node_.get(), - impl_->camera_name_ + "/" + MultiCameraPlugin::camera_[i]->Name() + "/image_raw")); + impl_->image_pub_.push_back( + image_transport::create_publisher( + impl_->ros_node_.get(), + impl_->camera_name_ + "/" + MultiCameraPlugin::camera_[i]->Name() + "/image_raw")); - // RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing %s camera images to [%s]", + // RCLCPP_INFO( + // impl_->ros_node_->get_logger(), "Publishing %s camera images to [%s]", // MultiCameraPlugin::camera_[i]->Name().c_str(), // impl_->image_pub_.back().getTopic()); @@ -207,7 +213,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ impl_->camera_name_ + "/" + MultiCameraPlugin::camera_[i]->Name() + "/camera_info", rclcpp::SensorDataQoS())); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing %s camera info to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing %s camera info to [%s]", MultiCameraPlugin::camera_[i]->Name().c_str(), impl_->camera_info_pub_[i]->get_topic_name()); } @@ -215,8 +222,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ if (impl_->sensor_type_ == GazeboRosCameraPrivate::DEPTH) { // Depth image publisher - impl_->depth_image_pub_ = image_transport::create_publisher(impl_->ros_node_.get(), - impl_->camera_name_ + "/depth/image_raw"); + impl_->depth_image_pub_ = image_transport::create_publisher( + impl_->ros_node_.get(), impl_->camera_name_ + "/depth/image_raw"); // RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing depth images to [%s]", // impl_->depth_image_pub_.getTopic().c_str()); @@ -226,14 +233,16 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ impl_->ros_node_->create_publisher( impl_->camera_name_ + "/depth/camera_info", rclcpp::QoS(rclcpp::KeepLast(1))); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing depth camera info to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing depth camera info to [%s]", impl_->depth_camera_info_pub_->get_topic_name()); // Point cloud publisher impl_->point_cloud_pub_ = impl_->ros_node_->create_publisher( impl_->camera_name_ + "/points", rclcpp::QoS(rclcpp::KeepLast(1))); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing pointcloud to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing pointcloud to [%s]", impl_->point_cloud_pub_->get_topic_name()); } @@ -244,7 +253,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ rclcpp::QoS(rclcpp::KeepLast(1)), std::bind(&GazeboRosCamera::OnTrigger, this, std::placeholders::_1)); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Subscribed to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Subscribed to [%s]", impl_->trigger_sub_->get_topic_name()); SetCameraEnabled(false); @@ -279,22 +289,26 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ impl_->img_encoding_.emplace_back(sensor_msgs::image_encodings::RGB16); impl_->img_step_.push_back(6); } else if (format == "BAYER_RGGB8") { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "bayer simulation may be computationally expensive."); impl_->img_encoding_.emplace_back(sensor_msgs::image_encodings::BAYER_RGGB8); impl_->img_step_.push_back(1); } else if (format == "BAYER_BGGR8") { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "bayer simulation may be computationally expensive."); impl_->img_encoding_.emplace_back(sensor_msgs::image_encodings::BAYER_BGGR8); impl_->img_step_.push_back(1); } else if (format == "BAYER_GBRG8") { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "bayer simulation may be computationally expensive."); impl_->img_encoding_.emplace_back(sensor_msgs::image_encodings::BAYER_GBRG8); impl_->img_step_.push_back(1); } else if (format == "BAYER_GRBG8") { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "bayer simulation may be computationally expensive."); impl_->img_encoding_.emplace_back(sensor_msgs::image_encodings::BAYER_GRBG8); impl_->img_step_.push_back(1); @@ -338,7 +352,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ if (focal_length == 0) { focal_length = computed_focal_length; } else if (!ignition::math::equal(focal_length, computed_focal_length)) { - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "The [%f] you have provided for camera [%s]" " is inconsistent with specified [%d] and" " HFOV [%f]. Please double check to see that" @@ -425,7 +440,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ camera_info_msg.p[11] = 0.0; // Initialize camera_info_manager - impl_->camera_info_manager_.push_back(std::make_shared( + impl_->camera_info_manager_.push_back( + std::make_shared( impl_->ros_node_.get(), impl_->camera_name_)); impl_->camera_info_manager_.back()->setCameraInfo(camera_info_msg); } @@ -485,7 +501,8 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ std::string param_name = parameter.get_name(); if (param_name == "update_rate") { if (nullptr != impl_->trigger_sub_) { - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "Cannot set update rate for triggered camera"); result.successful = false; } else { @@ -502,14 +519,17 @@ void GazeboRosCamera::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _ } if (rate >= 0.0) { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Camera update rate changed to [%.2f Hz]", rate); } else { - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "Camera update rate should be positive. Setting to maximum"); } } else { - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "Value for param [update_rate] has to be of double type."); result.successful = false; } @@ -555,7 +575,8 @@ void GazeboRosCamera::NewFrame( sensor_update_time); // Copy from src to image_msg - sensor_msgs::fillImage(impl_->image_msg_, impl_->img_encoding_[_camera_num], _height, _width, + sensor_msgs::fillImage( + impl_->image_msg_, impl_->img_encoding_[_camera_num], _height, _width, impl_->img_step_[_camera_num] * _width, reinterpret_cast(_image)); impl_->image_pub_[_camera_num].publish(impl_->image_msg_); @@ -708,10 +729,12 @@ void GazeboRosCamera::OnNewDepthFrame( if (impl_->image_msg_.data.size() == _width * _height * 3) { // color - std::memcpy(&impl_->cloud_msg_.data[cloud_index + 16], + std::memcpy( + &impl_->cloud_msg_.data[cloud_index + 16], &impl_->image_msg_.data[(i + j * _width) * 3], 3 * sizeof(uint8_t)); } else if (impl_->image_msg_.data.size() == _height * _width) { - std::memcpy(&impl_->cloud_msg_.data[cloud_index + 16], + std::memcpy( + &impl_->cloud_msg_.data[cloud_index + 16], &impl_->image_msg_.data[i + j * _width], 3 * sizeof(uint8_t)); } else { // no image diff --git a/gazebo_plugins/src/gazebo_ros_diff_drive.cpp b/gazebo_plugins/src/gazebo_ros_diff_drive.cpp index 1c70c5502..fd8d6246b 100644 --- a/gazebo_plugins/src/gazebo_ros_diff_drive.cpp +++ b/gazebo_plugins/src/gazebo_ros_diff_drive.cpp @@ -241,7 +241,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr if (impl_->num_wheel_pairs_ < 1) { impl_->num_wheel_pairs_ = 1; - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "Drive requires at least one pair of wheels. Setting [num_wheel_pairs] to 1"); } @@ -258,7 +259,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr auto left_joint_name = left_joint_elem->Get(); auto left_joint = _model->GetJoint(left_joint_name); if (!left_joint) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Joint [%s] not found, plugin will not work.", left_joint_name.c_str()); impl_->ros_node_.reset(); return; @@ -273,7 +275,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr auto right_joint_name = right_joint_elem->Get(); auto right_joint = _model->GetJoint(right_joint_name); if (!right_joint) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Joint [%s] not found, plugin will not work.", right_joint_name.c_str()); impl_->ros_node_.reset(); return; @@ -283,7 +286,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr } if (left_joints.size() != right_joints.size() || left_joints.size() != impl_->num_wheel_pairs_) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Inconsistent number of joints specified. Plugin will not work."); impl_->ros_node_.reset(); return; @@ -305,7 +309,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr break; } impl_->wheel_separation_[index] = wheel_separation->Get(); - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Wheel pair %i separation set to [%fm]", index + 1, impl_->wheel_separation_[index]); index++; } @@ -320,7 +325,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr break; } impl_->wheel_diameter_[index] = wheel_diameter->Get(); - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Wheel pair %i diameter set to [%fm]", index + 1, impl_->wheel_diameter_[index]); index++; } @@ -341,7 +347,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr "cmd_vel", rclcpp::QoS(rclcpp::KeepLast(1)), std::bind(&GazeboRosDiffDrivePrivate::OnCmdVel, impl_.get(), std::placeholders::_1)); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Subscribed to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Subscribed to [%s]", impl_->cmd_vel_sub_->get_topic_name()); // Odometry @@ -356,7 +363,8 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr 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]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise odometry on [%s]", impl_->odometry_pub_->get_topic_name()); } @@ -368,14 +376,16 @@ void GazeboRosDiffDrive::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr std::make_shared(impl_->ros_node_); if (impl_->publish_odom_tf_) { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + 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()); } for (index = 0; index < impl_->num_wheel_pairs_; ++index) { if (impl_->publish_wheel_tf_) { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing wheel transforms between [%s], [%s] and [%s]", impl_->robot_base_frame_.c_str(), impl_->joints_[2 * index + GazeboRosDiffDrivePrivate::LEFT]->GetName().c_str(), @@ -468,19 +478,23 @@ void GazeboRosDiffDrivePrivate::OnUpdate(const gazebo::common::UpdateInfo & _inf "vel", 0, desired_wheel_speed_[2 * i + RIGHT] / (wheel_diameter_[i] / 2.0)); } else { if (desired_wheel_speed_[2 * i + LEFT] >= current_speed[2 * i + LEFT]) { - wheel_speed_instr_[2 * i + LEFT] += fmin(desired_wheel_speed_[2 * i + LEFT] - - current_speed[2 * i + LEFT], max_wheel_accel_ * seconds_since_last_update); + wheel_speed_instr_[2 * i + LEFT] += fmin( + desired_wheel_speed_[2 * i + LEFT] - + current_speed[2 * i + LEFT], max_wheel_accel_ * seconds_since_last_update); } else { - wheel_speed_instr_[2 * i + LEFT] += fmax(desired_wheel_speed_[2 * i + LEFT] - - current_speed[2 * i + LEFT], -max_wheel_accel_ * seconds_since_last_update); + wheel_speed_instr_[2 * i + LEFT] += fmax( + desired_wheel_speed_[2 * i + LEFT] - + current_speed[2 * i + LEFT], -max_wheel_accel_ * seconds_since_last_update); } if (desired_wheel_speed_[2 * i + RIGHT] > current_speed[2 * i + RIGHT]) { - wheel_speed_instr_[2 * i + RIGHT] += fmin(desired_wheel_speed_[2 * i + RIGHT] - - current_speed[2 * i + RIGHT], max_wheel_accel_ * seconds_since_last_update); + wheel_speed_instr_[2 * i + RIGHT] += fmin( + desired_wheel_speed_[2 * i + RIGHT] - + current_speed[2 * i + RIGHT], max_wheel_accel_ * seconds_since_last_update); } else { - wheel_speed_instr_[2 * i + RIGHT] += fmax(desired_wheel_speed_[2 * i + RIGHT] - - current_speed[2 * i + RIGHT], -max_wheel_accel_ * seconds_since_last_update); + wheel_speed_instr_[2 * i + RIGHT] += fmax( + desired_wheel_speed_[2 * i + RIGHT] - + current_speed[2 * i + RIGHT], -max_wheel_accel_ * seconds_since_last_update); } joints_[2 * i + LEFT]->SetParam( diff --git a/gazebo_plugins/src/gazebo_ros_force.cpp b/gazebo_plugins/src/gazebo_ros_force.cpp index 09af745da..c43635d54 100644 --- a/gazebo_plugins/src/gazebo_ros_force.cpp +++ b/gazebo_plugins/src/gazebo_ros_force.cpp @@ -77,7 +77,8 @@ void GazeboRosForce::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) // Force frame if (!sdf->HasElement("force_frame")) { - RCLCPP_INFO(logger, "Force plugin missing wasn't set," + RCLCPP_INFO( + logger, "Force plugin missing wasn't set," "therefore it's been set as 'world'. The other option is 'link'."); impl_->force_on_world_frame_ = true; } else { diff --git a/gazebo_plugins/src/gazebo_ros_ft_sensor.cpp b/gazebo_plugins/src/gazebo_ros_ft_sensor.cpp index 543ea6e80..f1ed0284b 100644 --- a/gazebo_plugins/src/gazebo_ros_ft_sensor.cpp +++ b/gazebo_plugins/src/gazebo_ros_ft_sensor.cpp @@ -92,13 +92,15 @@ void GazeboRosFTSensor::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _ impl_->rosnode_ = gazebo_ros::Node::Get(_sdf); if (!_sdf->HasElement("update_rate")) { - RCLCPP_DEBUG(impl_->rosnode_->get_logger(), + RCLCPP_DEBUG( + impl_->rosnode_->get_logger(), "ft_sensor plugin missing , defaults to 0.0 (as fast as possible)"); } impl_->update_rate_ = _sdf->Get("update_rate", 0.0).first; if (!_sdf->HasElement("body_name") && !_sdf->HasElement("joint_name")) { - RCLCPP_ERROR(impl_->rosnode_->get_logger(), + RCLCPP_ERROR( + impl_->rosnode_->get_logger(), "ft_sensor plugin missing and , cannot proceed"); impl_->rosnode_.reset(); return; @@ -110,7 +112,8 @@ void GazeboRosFTSensor::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _ impl_->link_ = _model->GetLink(link_name); if (!impl_->link_) { - RCLCPP_ERROR(impl_->rosnode_->get_logger(), + RCLCPP_ERROR( + impl_->rosnode_->get_logger(), "Link [%s] does not exist. Aborting", link_name.c_str()); impl_->rosnode_.reset(); return; @@ -123,20 +126,23 @@ void GazeboRosFTSensor::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _ impl_->joint_ = _model->GetJoint(joint_name); if (!impl_->joint_) { - RCLCPP_ERROR(impl_->rosnode_->get_logger(), + RCLCPP_ERROR( + impl_->rosnode_->get_logger(), "Joint [%s] does not exist. Aborting", joint_name.c_str()); impl_->rosnode_.reset(); return; } if (_sdf->HasElement("frame_name")) { - RCLCPP_WARN(impl_->rosnode_->get_logger(), + RCLCPP_WARN( + impl_->rosnode_->get_logger(), " can be set only for ft_sensor on links."); } impl_->frame_id_ = impl_->joint_->GetChild()->GetName(); } - RCLCPP_INFO(impl_->rosnode_->get_logger(), + RCLCPP_INFO( + impl_->rosnode_->get_logger(), "ft_sensor plugin reporting wrench values to the frame [%s]", impl_->frame_id_.c_str()); if (!_sdf->HasElement("gaussian_noise")) { @@ -144,11 +150,12 @@ void GazeboRosFTSensor::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _ } impl_->gaussian_noise_ = _sdf->Get("gaussian_noise", 0.0).first; - impl_->pub_ = - impl_->rosnode_->create_publisher("wrench", - rclcpp::QoS(rclcpp::KeepLast(1))); + impl_->pub_ = impl_->rosnode_->create_publisher( + "wrench", + rclcpp::QoS(rclcpp::KeepLast(1))); - RCLCPP_INFO(impl_->rosnode_->get_logger(), + RCLCPP_INFO( + impl_->rosnode_->get_logger(), "Publishing wrenches on topic [%s]", impl_->pub_->get_topic_name()); impl_->last_time_ = _model->GetWorld()->SimTime(); diff --git a/gazebo_plugins/src/gazebo_ros_hand_of_god.cpp b/gazebo_plugins/src/gazebo_ros_hand_of_god.cpp index f568772a1..ba30abff6 100644 --- a/gazebo_plugins/src/gazebo_ros_hand_of_god.cpp +++ b/gazebo_plugins/src/gazebo_ros_hand_of_god.cpp @@ -110,8 +110,8 @@ void GazeboRosHandOfGod::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr auto link_name = _sdf->Get("link_name"); impl_->link_ = _model->GetLink(link_name); if (!impl_->link_) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), - "Link [%s] not found. Aborting", link_name.c_str()); + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Link [%s] not found. Aborting", link_name.c_str()); impl_->ros_node_.reset(); return; } diff --git a/gazebo_plugins/src/gazebo_ros_harness.cpp b/gazebo_plugins/src/gazebo_ros_harness.cpp index 14f73e882..c5aab4515 100644 --- a/gazebo_plugins/src/gazebo_ros_harness.cpp +++ b/gazebo_plugins/src/gazebo_ros_harness.cpp @@ -67,15 +67,15 @@ void GazeboRosHarness::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _s SetWinchVelocity(msg->data); }); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Subscribed to [%s]", - impl_->vel_sub_->get_topic_name()); + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Subscribed to [%s]", impl_->vel_sub_->get_topic_name()); impl_->detach_sub_ = impl_->ros_node_->create_subscription( impl_->model_ + "/harness/detach", rclcpp::QoS(rclcpp::KeepLast(1)), std::bind(&GazeboRosHarness::OnDetach, this, std::placeholders::_1)); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Subscribed to [%s]", - impl_->detach_sub_->get_topic_name()); + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Subscribed to [%s]", impl_->detach_sub_->get_topic_name()); if (_sdf->HasElement("init_vel")) { auto init_vel = _sdf->Get("init_vel"); @@ -88,7 +88,8 @@ void GazeboRosHarness::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _s void GazeboRosHarness::OnDetach(const std_msgs::msg::Empty::ConstSharedPtr /*msg*/) { if (impl_->detached_) { - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "[%s] is already detached from harness", impl_->model_.c_str()); return; } diff --git a/gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp b/gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp index e0fb1e0f1..56092ba71 100644 --- a/gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp +++ b/gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp @@ -121,8 +121,9 @@ void GazeboRosJointPoseTrajectory::Load(gazebo::physics::ModelPtr model, sdf::El // Set Joint Trajectory Callback impl_->sub_ = impl_->ros_node_->create_subscription( "set_joint_trajectory", rclcpp::QoS(rclcpp::KeepLast(1)), - std::bind(&GazeboRosJointPoseTrajectoryPrivate::SetJointTrajectory, - impl_.get(), std::placeholders::_1)); + std::bind( + &GazeboRosJointPoseTrajectoryPrivate::SetJointTrajectory, + impl_.get(), std::placeholders::_1)); // Callback on every iteration impl_->update_connection_ = gazebo::event::Events::ConnectWorldUpdateBegin( @@ -149,7 +150,8 @@ void GazeboRosJointPoseTrajectoryPrivate::OnUpdate(const gazebo::common::UpdateI std::lock_guard scoped_lock(lock_); if (has_trajectory_ && current_time >= trajectory_start_time_) { if (trajectory_index_ < points_.size()) { - RCLCPP_INFO(ros_node_->get_logger(), "time [%f] updating configuration [%d/%lu]", + RCLCPP_INFO( + ros_node_->get_logger(), "time [%f] updating configuration [%d/%lu]", current_time.Double(), trajectory_index_ + 1, points_.size()); // get reference link pose before updates @@ -176,7 +178,8 @@ void GazeboRosJointPoseTrajectoryPrivate::OnUpdate(const gazebo::common::UpdateI model_->SetWorldPose(reference_pose); } } else { - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "point[%u] has different number of joint names[%u] and positions[%lu].", trajectory_index_ + 1, chain_size, points_[trajectory_index_].positions.size()); } @@ -213,12 +216,14 @@ void GazeboRosJointPoseTrajectoryPrivate::SetJointTrajectory( reference_link_ = boost::dynamic_pointer_cast(entity); } if (!reference_link_) { - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "Plugin needs a reference link [%s] as frame_id, aborting.", reference_link_name.c_str()); return; } model_ = reference_link_->GetParentModel(); - RCLCPP_DEBUG(ros_node_->get_logger(), + RCLCPP_DEBUG( + ros_node_->get_logger(), "Update model pose by keeping link [%s] stationary inertially", reference_link_->GetName().c_str()); } @@ -229,7 +234,8 @@ void GazeboRosJointPoseTrajectoryPrivate::SetJointTrajectory( for (unsigned int i = 0; i < chain_size; ++i) { joints_[i] = model_->GetJoint(msg->joint_names[i]); if (!joints_[i]) { - RCLCPP_ERROR(ros_node_->get_logger(), "Joint [%s] not found. Trajectory not set.", + RCLCPP_ERROR( + ros_node_->get_logger(), "Joint [%s] not found. Trajectory not set.", msg->joint_names[i].c_str()); return; } diff --git a/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp b/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp index 0905875da..90ae53f1f 100644 --- a/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp +++ b/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp @@ -103,7 +103,8 @@ void GazeboRosJointStatePublisher::Load(gazebo::physics::ModelPtr model, sdf::El RCLCPP_ERROR(impl_->ros_node_->get_logger(), "Joint %s does not exist!", joint_name.c_str()); } else { impl_->joints_.push_back(joint); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Going to publish joint [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Going to publish joint [%s]", joint_name.c_str() ); } @@ -119,8 +120,8 @@ void GazeboRosJointStatePublisher::Load(gazebo::physics::ModelPtr model, sdf::El // Update rate double update_rate = 100.0; if (!sdf->HasElement("update_rate")) { - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Missing , defaults to %f", - update_rate); + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Missing , defaults to %f", update_rate); } else { update_rate = sdf->GetElement("update_rate")->Get(); } diff --git a/gazebo_plugins/src/gazebo_ros_p3d.cpp b/gazebo_plugins/src/gazebo_ros_p3d.cpp index eb96b8905..1292a4db1 100644 --- a/gazebo_plugins/src/gazebo_ros_p3d.cpp +++ b/gazebo_plugins/src/gazebo_ros_p3d.cpp @@ -93,7 +93,8 @@ void GazeboRosP3D::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) impl_->ros_node_ = gazebo_ros::Node::Get(sdf); if (!sdf->HasElement("update_rate")) { - RCLCPP_DEBUG(impl_->ros_node_->get_logger(), "p3d plugin missing , defaults to 0.0" + RCLCPP_DEBUG( + impl_->ros_node_->get_logger(), "p3d plugin missing , defaults to 0.0" " (as fast as possible)"); } else { impl_->update_rate_ = sdf->GetElement("update_rate")->Get(); @@ -130,8 +131,8 @@ void GazeboRosP3D::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) if (!sdf->HasElement("rpy_offsets")) { RCLCPP_DEBUG(impl_->ros_node_->get_logger(), "Missing , defaults to 0s"); } else { - impl_->offset_.Rot() = ignition::math::Quaterniond(sdf->GetElement( - "rpy_offsets")->Get()); + impl_->offset_.Rot() = ignition::math::Quaterniond( + sdf->GetElement("rpy_offsets")->Get()); } if (!sdf->HasElement("gaussian_noise")) { @@ -157,7 +158,8 @@ void GazeboRosP3D::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) { impl_->reference_link_ = model->GetLink(impl_->frame_name_); if (!impl_->reference_link_) { - RCLCPP_WARN(impl_->ros_node_->get_logger(), " [%s] does not exist.", + RCLCPP_WARN( + impl_->ros_node_->get_logger(), " [%s] does not exist.", impl_->frame_name_.c_str()); } } diff --git a/gazebo_plugins/src/gazebo_ros_planar_move.cpp b/gazebo_plugins/src/gazebo_ros_planar_move.cpp index 266cb57f8..b807fa4b9 100644 --- a/gazebo_plugins/src/gazebo_ros_planar_move.cpp +++ b/gazebo_plugins/src/gazebo_ros_planar_move.cpp @@ -157,7 +157,8 @@ void GazeboRosPlanarMove::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr "cmd_vel", rclcpp::QoS(rclcpp::KeepLast(1)), std::bind(&GazeboRosPlanarMovePrivate::OnCmdVel, impl_.get(), std::placeholders::_1)); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Subscribed to [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Subscribed to [%s]", impl_->cmd_vel_sub_->get_topic_name()); // Advertise odometry topic @@ -166,7 +167,8 @@ void GazeboRosPlanarMove::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr 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]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise odometry on [%s]", impl_->odometry_pub_->get_topic_name()); } @@ -176,7 +178,8 @@ void GazeboRosPlanarMove::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr impl_->transform_broadcaster_ = std::make_shared(impl_->ros_node_); - RCLCPP_INFO(impl_->ros_node_->get_logger(), + 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()); } @@ -226,7 +229,8 @@ void GazeboRosPlanarMovePrivate::OnUpdate(const gazebo::common::UpdateInfo & _in if (seconds_since_last_update >= update_period_) { ignition::math::Pose3d pose = model_->WorldPose(); auto yaw = static_cast(pose.Rot().Yaw()); - model_->SetLinearVel(ignition::math::Vector3d( + model_->SetLinearVel( + ignition::math::Vector3d( target_cmd_vel_.linear.x * cosf(yaw) - target_cmd_vel_.linear.y * sinf(yaw), target_cmd_vel_.linear.y * cosf(yaw) + target_cmd_vel_.linear.x * sinf(yaw), 0)); diff --git a/gazebo_plugins/src/gazebo_ros_projector.cpp b/gazebo_plugins/src/gazebo_ros_projector.cpp index fc4ef5fca..a488c256f 100644 --- a/gazebo_plugins/src/gazebo_ros_projector.cpp +++ b/gazebo_plugins/src/gazebo_ros_projector.cpp @@ -80,15 +80,16 @@ void GazeboRosProjector::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr // Create a Gazebo publisher to switch the projector impl_->projector_pub_ = impl_->gazebo_node_->Advertise(name); - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Controlling projector at [%s]", impl_->projector_pub_->GetTopic().c_str()); impl_->toggle_sub_ = impl_->ros_node_->create_subscription( "switch", rclcpp::QoS(rclcpp::KeepLast(1)), std::bind(&GazeboRosProjectorPrivate::ToggleProjector, impl_.get(), std::placeholders::_1)); - RCLCPP_INFO(impl_->ros_node_->get_logger(), - "Subscribed to [%s]", impl_->toggle_sub_->get_topic_name()); + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Subscribed to [%s]", impl_->toggle_sub_->get_topic_name()); } void GazeboRosProjectorPrivate::ToggleProjector(const std_msgs::msg::Bool::SharedPtr switch_msg) diff --git a/gazebo_plugins/src/gazebo_ros_ray_sensor.cpp b/gazebo_plugins/src/gazebo_ros_ray_sensor.cpp index 6d0fc4c01..1052da7d6 100644 --- a/gazebo_plugins/src/gazebo_ros_ray_sensor.cpp +++ b/gazebo_plugins/src/gazebo_ros_ray_sensor.cpp @@ -126,8 +126,8 @@ void GazeboRosRaySensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt impl_->pub_ = impl_->ros_node_->create_publisher( "~/out", rclcpp::SensorDataQoS()); } else { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), "Invalid [%s]", - output_type_string.c_str()); + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Invalid [%s]", output_type_string.c_str()); return; } } @@ -135,8 +135,8 @@ void GazeboRosRaySensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt // Get parameters specific to Range output from sdf if (impl_->pub_.type() == typeid(GazeboRosRaySensorPrivate::RangePub)) { if (!_sdf->HasElement("radiation_type")) { - RCLCPP_INFO(impl_->ros_node_->get_logger(), - "missing , defaulting to infrared"); + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "missing , defaulting to infrared"); impl_->range_radiation_type_ = sensor_msgs::msg::Range::INFRARED; } else if ("ultrasound" == _sdf->Get("radiation_type")) { impl_->range_radiation_type_ = sensor_msgs::msg::Range::ULTRASOUND; @@ -152,7 +152,8 @@ void GazeboRosRaySensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt } if (!_sdf->HasElement("min_intensity")) { - RCLCPP_DEBUG(impl_->ros_node_->get_logger(), "missing , defaults to %f", + RCLCPP_DEBUG( + impl_->ros_node_->get_logger(), "missing , defaults to %f", impl_->min_intensity_); } else { impl_->min_intensity_ = _sdf->Get("min_intensity"); @@ -170,17 +171,17 @@ void GazeboRosRaySensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt void GazeboRosRaySensorPrivate::SubscribeGazeboLaserScan() { if (pub_.type() == typeid(LaserScanPub)) { - laser_scan_sub_ = gazebo_node_->Subscribe(sensor_topic_, - &GazeboRosRaySensorPrivate::PublishLaserScan, this); + laser_scan_sub_ = gazebo_node_->Subscribe( + sensor_topic_, &GazeboRosRaySensorPrivate::PublishLaserScan, this); } else if (pub_.type() == typeid(PointCloudPub)) { - laser_scan_sub_ = gazebo_node_->Subscribe(sensor_topic_, - &GazeboRosRaySensorPrivate::PublishPointCloud, this); + laser_scan_sub_ = gazebo_node_->Subscribe( + sensor_topic_, &GazeboRosRaySensorPrivate::PublishPointCloud, this); } else if (pub_.type() == typeid(PointCloud2Pub)) { - laser_scan_sub_ = gazebo_node_->Subscribe(sensor_topic_, - &GazeboRosRaySensorPrivate::PublishPointCloud2, this); + laser_scan_sub_ = gazebo_node_->Subscribe( + sensor_topic_, &GazeboRosRaySensorPrivate::PublishPointCloud2, this); } else if (pub_.type() == typeid(RangePub)) { - laser_scan_sub_ = gazebo_node_->Subscribe(sensor_topic_, - &GazeboRosRaySensorPrivate::PublishRange, this); + laser_scan_sub_ = gazebo_node_->Subscribe( + sensor_topic_, &GazeboRosRaySensorPrivate::PublishRange, this); } else { RCLCPP_ERROR(ros_node_->get_logger(), "Publisher is an invalid type. This is an internal bug."); } diff --git a/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp b/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp index 49eebf1d1..8448ef4aa 100644 --- a/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp +++ b/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp @@ -264,7 +264,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element auto steering_joint = _sdf->Get("steering_joint", "front_steering_joint").first; impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING] = _model->GetJoint(steering_joint); if (!impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING]) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Steering joint [%s] not found, plugin will not work.", steering_joint.c_str()); impl_->ros_node_.reset(); return; @@ -275,7 +276,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ACTUATED] = _model->GetJoint( wheel_actuated_joint); if (!impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ACTUATED]) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Wheel actuated joint [%s] not found, plugin will not work.", wheel_actuated_joint.c_str()); impl_->ros_node_.reset(); @@ -287,7 +289,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ENCODER_LEFT] = _model->GetJoint( wheel_encoder_left_joint); if (!impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ENCODER_LEFT]) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Left wheel encoder joint [%s] not found, plugin will not work.", wheel_encoder_left_joint.c_str()); impl_->ros_node_.reset(); @@ -299,7 +302,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ENCODER_RIGHT] = _model->GetJoint( wheel_encoder_right_joint); if (!impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ENCODER_RIGHT]) { - RCLCPP_ERROR(impl_->ros_node_->get_logger(), + RCLCPP_ERROR( + impl_->ros_node_->get_logger(), "Right wheel encoder joint [%s] not found, plugin will not work.", wheel_encoder_right_joint.c_str()); impl_->ros_node_.reset(); @@ -307,10 +311,10 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element } impl_->max_wheel_torque_ = _sdf->Get("max_wheel_torque", 0.15).first; - impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ACTUATED]->SetParam("fmax", 0, - impl_->max_wheel_torque_); - impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING]->SetParam("fmax", 0, - impl_->max_wheel_torque_); + impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ACTUATED]->SetParam( + "fmax", 0, impl_->max_wheel_torque_); + impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING]->SetParam( + "fmax", 0, impl_->max_wheel_torque_); // Update rate auto update_rate = _sdf->Get("update_rate", 100).first; @@ -325,8 +329,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element "cmd_vel", rclcpp::QoS(rclcpp::KeepLast(1)), std::bind(&GazeboRosTricycleDrivePrivate::OnCmdVel, impl_.get(), std::placeholders::_1)); - RCLCPP_INFO(impl_->ros_node_->get_logger(), - "Subscribe to [%s]", impl_->cmd_vel_sub_->get_topic_name()); + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Subscribe to [%s]", impl_->cmd_vel_sub_->get_topic_name()); impl_->publish_wheel_tf_ = _sdf->Get("publish_wheel_tf", false).first; @@ -334,7 +338,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element if (impl_->publish_wheel_joint_state_) { impl_->joint_state_publisher_ = impl_->ros_node_->create_publisher("joint_states", 1000); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Advertise joint_states on [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise joint_states on [%s]", impl_->joint_state_publisher_->get_topic_name()); } @@ -344,7 +349,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element 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]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise odometry on [%s]", impl_->odometry_pub_->get_topic_name()); } @@ -354,7 +360,8 @@ void GazeboRosTricycleDrive::Load(gazebo::physics::ModelPtr _model, sdf::Element impl_->ros_node_); if (impl_->publish_odom_) { - RCLCPP_INFO(impl_->ros_node_->get_logger(), + 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()); } @@ -397,10 +404,10 @@ void GazeboRosTricycleDrive::Reset() { gazebo::common::Time current_time = impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING]->GetWorld()->SimTime(); - impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ACTUATED]->SetParam("fmax", 0, - impl_->max_wheel_torque_); - impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING]->SetParam("fmax", 0, - impl_->max_wheel_torque_); + impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ACTUATED]->SetParam( + "fmax", 0, impl_->max_wheel_torque_); + impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING]->SetParam( + "fmax", 0, impl_->max_wheel_torque_); impl_->joints_[GazeboRosTricycleDrivePrivate::WHEEL_ACTUATED]->SetParam("vel", 0, 0.0); impl_->joints_[GazeboRosTricycleDrivePrivate::STEERING]->SetParam("vel", 0, 0.0); impl_->last_actuator_update_ = current_time; diff --git a/gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp b/gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp index c3102f840..5e4c3f644 100644 --- a/gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp +++ b/gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp @@ -116,7 +116,8 @@ void GazeboRosVacuumGripper::Load(gazebo::physics::ModelPtr _model, sdf::Element { auto name = fixed->Get(); impl_->fixed_.insert(name); - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Model/Link [%s] exempted from gripper force", name.c_str()); } } @@ -127,15 +128,19 @@ void GazeboRosVacuumGripper::Load(gazebo::physics::ModelPtr _model, sdf::Element impl_->pub_ = impl_->ros_node_->create_publisher( "grasping", rclcpp::QoS(rclcpp::KeepLast(1))); - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise gripper status on [%s]", impl_->pub_->get_topic_name()); // Initialize service - impl_->service_ = impl_->ros_node_->create_service("switch", - std::bind(&GazeboRosVacuumGripperPrivate::OnSwitch, impl_.get(), + impl_->service_ = impl_->ros_node_->create_service( + "switch", + std::bind( + &GazeboRosVacuumGripperPrivate::OnSwitch, impl_.get(), std::placeholders::_1, std::placeholders::_2)); - RCLCPP_INFO(impl_->ros_node_->get_logger(), + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Advertise gripper switch service on [%s]", impl_->service_->get_service_name()); // Listen to the update event (broadcast every simulation iteration) diff --git a/gazebo_plugins/src/gazebo_ros_video.cpp b/gazebo_plugins/src/gazebo_ros_video.cpp index 16abd2627..490614d7b 100644 --- a/gazebo_plugins/src/gazebo_ros_video.cpp +++ b/gazebo_plugins/src/gazebo_ros_video.cpp @@ -200,8 +200,8 @@ void GazeboRosVideo::Load( int width = _sdf->Get("width", 320).first; - impl_->video_visual_ = std::make_shared(_parent->Name() + "::video_visual::" + - _sdf->Get("name"), _parent, height, width); + impl_->video_visual_ = std::make_shared( + _parent->Name() + "::video_visual::" + _sdf->Get("name"), _parent, height, width); _parent->GetScene()->AddVisual(impl_->video_visual_); // Subscribe to the image topic @@ -215,7 +215,8 @@ void GazeboRosVideo::Load( impl_->update_connection_ = gazebo::event::Events::ConnectPreRender( std::bind(&GazeboRosVideoPrivate::onUpdate, impl_.get())); - RCLCPP_INFO(impl_->rosnode_->get_logger(), + RCLCPP_INFO( + impl_->rosnode_->get_logger(), "GazeboRosVideo has started. Subscribed to [%s]", impl_->camera_subscriber_->get_topic_name()); } diff --git a/gazebo_plugins/src/multi_camera_plugin.cpp b/gazebo_plugins/src/multi_camera_plugin.cpp index af5901781..bee938972 100644 --- a/gazebo_plugins/src/multi_camera_plugin.cpp +++ b/gazebo_plugins/src/multi_camera_plugin.cpp @@ -81,10 +81,12 @@ void MultiCameraPlugin::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr depth_.push_back(camera_[i]->ImageDepth()); format_.push_back(camera_[i]->ImageFormat()); - impl_->new_frame_connection_.push_back(camera_[i]->ConnectNewImageFrame( - std::bind(&MultiCameraPlugin::OnNewMultiFrame, - this, std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, i))); + impl_->new_frame_connection_.push_back( + camera_[i]->ConnectNewImageFrame( + std::bind( + &MultiCameraPlugin::OnNewMultiFrame, + this, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, i))); } parent_sensor_->SetActive(true); diff --git a/gazebo_plugins/test/test_gazebo_ros_camera.cpp b/gazebo_plugins/test/test_gazebo_ros_camera.cpp index db704cfa1..66603211e 100644 --- a/gazebo_plugins/test/test_gazebo_ros_camera.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_camera.cpp @@ -57,12 +57,13 @@ TEST_P(GazeboRosCameraTest, CameraSubscribeTest) unsigned int msg_count{0}; builtin_interfaces::msg::Time image_stamp; - auto sub = image_transport::create_subscription(node.get(), GetParam().topic, - [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { - image_stamp = msg->header.stamp; - ++msg_count; - }, - "raw"); + auto sub = image_transport::create_subscription( + node.get(), GetParam().topic, + [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { + image_stamp = msg->header.stamp; + ++msg_count; + }, + "raw"); // Update rate is 0.5 Hz, so we step 3s sim time to be sure we get exactly 1 image at 2s world->Step(3000); @@ -80,11 +81,10 @@ TEST_P(GazeboRosCameraTest, CameraSubscribeTest) sub.shutdown(); } -INSTANTIATE_TEST_CASE_P(GazeboRosCamera, GazeboRosCameraTest, ::testing::Values( - TestParams({"worlds/gazebo_ros_camera.world", - "test_cam/camera/image_test"}), - TestParams({"worlds/gazebo_ros_camera_16bit.world", - "test_cam_16bit/image_test_16bit"}) +INSTANTIATE_TEST_CASE_P( + GazeboRosCamera, GazeboRosCameraTest, ::testing::Values( + TestParams({"worlds/gazebo_ros_camera.world", "test_cam/camera/image_test"}), + TestParams({"worlds/gazebo_ros_camera_16bit.world", "test_cam_16bit/image_test_16bit"}) ), ); int main(int argc, char ** argv) diff --git a/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp b/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp index 6bc4037a5..5fab7ae89 100644 --- a/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp @@ -99,21 +99,23 @@ TEST_P(GazeboRosCameraDistortionTest, CameraSubscribeTest) // Subscribe to undistorted image sensor_msgs::msg::Image::ConstSharedPtr cam_image_undistorted; - cam_sub_undistorted_ = image_transport::create_subscription(node.get(), - GetParam().undistorted_topic, - [&cam_image_undistorted](const sensor_msgs::msg::Image::ConstSharedPtr & _msg) { - cam_image_undistorted = _msg; - }, - "raw"); + cam_sub_undistorted_ = image_transport::create_subscription( + node.get(), + GetParam().undistorted_topic, + [&cam_image_undistorted](const sensor_msgs::msg::Image::ConstSharedPtr & _msg) { + cam_image_undistorted = _msg; + }, + "raw"); // Subscribe to distorted image sensor_msgs::msg::Image::ConstSharedPtr cam_image_distorted; - cam_sub_distorted_ = image_transport::create_subscription(node.get(), - GetParam().distorted_topic, - [&cam_image_distorted](const sensor_msgs::msg::Image::ConstSharedPtr & _msg) { - cam_image_distorted = _msg; - }, - "raw"); + cam_sub_distorted_ = image_transport::create_subscription( + node.get(), + GetParam().distorted_topic, + [&cam_image_distorted](const sensor_msgs::msg::Image::ConstSharedPtr & _msg) { + cam_image_distorted = _msg; + }, + "raw"); // Subscribe to distorted camera info sensor_msgs::msg::CameraInfo::SharedPtr cam_info_distorted; @@ -143,13 +145,15 @@ TEST_P(GazeboRosCameraDistortionTest, CameraSubscribeTest) // Load camera coefficients from published ROS information auto intrinsic_distorted_matrix = cv::Mat(3, 3, CV_64F); if (cam_info_distorted->k.size() == 9) { - memcpy(intrinsic_distorted_matrix.data, cam_info_distorted->k.data(), + memcpy( + intrinsic_distorted_matrix.data, cam_info_distorted->k.data(), cam_info_distorted->k.size() * sizeof(double)); } auto distortion_coeffs = cv::Mat(5, 1, CV_64F); if (cam_info_distorted->d.size() == 5) { - memcpy(distortion_coeffs.data, cam_info_distorted->d.data(), + memcpy( + distortion_coeffs.data, cam_info_distorted->d.data(), cam_info_distorted->d.size() * sizeof(double)); } @@ -204,16 +208,18 @@ TEST_P(GazeboRosCameraDistortionTest, CameraSubscribeTest) } } -INSTANTIATE_TEST_CASE_P(GazeboRosCameraDistortion, GazeboRosCameraDistortionTest, - ::testing::Values( - TestParams({"worlds/gazebo_ros_camera_distortion_barrel.world", - "undistorted_image", - "distorted_image", - "distorted_info"}), - TestParams({"worlds/gazebo_ros_camera_distortion_pincushion.world", - "undistorted_image", - "distorted_image", - "distorted_info"}) +INSTANTIATE_TEST_CASE_P( + GazeboRosCameraDistortion, GazeboRosCameraDistortionTest, ::testing::Values( + TestParams( + {"worlds/gazebo_ros_camera_distortion_barrel.world", + "undistorted_image", + "distorted_image", + "distorted_info"}), + TestParams( + {"worlds/gazebo_ros_camera_distortion_pincushion.world", + "undistorted_image", + "distorted_image", + "distorted_info"}) ), ); int main(int argc, char ** argv) diff --git a/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp b/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp index 1618d1a9c..89a723391 100644 --- a/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp @@ -48,13 +48,14 @@ TEST_F(GazeboRosTriggeredCameraTest, CameraSubscribeTest) unsigned int msg_count{0}; builtin_interfaces::msg::Time image_stamp; - auto sub = image_transport::create_subscription(node.get(), - "test_triggered_cam/image_raw_test", - [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { - image_stamp = msg->header.stamp; - ++msg_count; - }, - "raw"); + auto sub = image_transport::create_subscription( + node.get(), + "test_triggered_cam/image_raw_test", + [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { + image_stamp = msg->header.stamp; + ++msg_count; + }, + "raw"); // Step a bit and check that we do not get any messages world->Step(100); diff --git a/gazebo_plugins/test/test_gazebo_ros_depth_camera.cpp b/gazebo_plugins/test/test_gazebo_ros_depth_camera.cpp index 241659ea3..5283e7ddc 100644 --- a/gazebo_plugins/test/test_gazebo_ros_depth_camera.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_depth_camera.cpp @@ -64,11 +64,12 @@ TEST_P(GazeboRosDepthCameraTest, DepthCameraSubscribeTest) unsigned int msg_count{0}; builtin_interfaces::msg::Time image_stamp; - auto sub = image_transport::create_subscription(node.get(), GetParam().raw_image_topic, - [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { - image_stamp = msg->header.stamp; - ++msg_count; - }, "raw"); + auto sub = image_transport::create_subscription( + node.get(), GetParam().raw_image_topic, + [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { + image_stamp = msg->header.stamp; + ++msg_count; + }, "raw"); // Update rate is 0.5 Hz, so we step 3s sim time to be sure we get exactly 1 image at 2s world->Step(3000); @@ -89,11 +90,12 @@ TEST_P(GazeboRosDepthCameraTest, DepthCameraSubscribeTest) unsigned int msg_count_depth{0}; builtin_interfaces::msg::Time image_stamp_depth; - auto sub_depth = image_transport::create_subscription(node.get(), GetParam().depth_image_topic, - [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { - image_stamp_depth = msg->header.stamp; - ++msg_count_depth; - }, "raw"); + auto sub_depth = image_transport::create_subscription( + node.get(), GetParam().depth_image_topic, + [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { + image_stamp_depth = msg->header.stamp; + ++msg_count_depth; + }, "raw"); // Update rate is 0.5 Hz, so we step 3s sim time to be sure we get exactly 1 image at 2s world->Step(3000); @@ -134,11 +136,13 @@ TEST_P(GazeboRosDepthCameraTest, DepthCameraSubscribeTest) EXPECT_EQ(8.0, image_stamp_pcl.sec); } -INSTANTIATE_TEST_CASE_P(GazeboRosDepthCamera, GazeboRosDepthCameraTest, ::testing::Values( - TestParams({"worlds/gazebo_ros_depth_camera.world", - "test_cam/camera/raw_image_test", - "test_cam/camera/depth_image_test", - "test_cam/camera/points_test"}) +INSTANTIATE_TEST_CASE_P( + GazeboRosDepthCamera, GazeboRosDepthCameraTest, ::testing::Values( + TestParams( + {"worlds/gazebo_ros_depth_camera.world", + "test_cam/camera/raw_image_test", + "test_cam/camera/depth_image_test", + "test_cam/camera/points_test"}) ), ); int main(int argc, char ** argv) diff --git a/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp b/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp index 0041c05a7..50dbfbe4b 100644 --- a/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_diff_drive.cpp @@ -122,7 +122,8 @@ TEST_P(GazeboRosDiffDriveTest, Publishing) EXPECT_NEAR(0.1, vehicle->WorldAngularVel().Z(), tol); } -INSTANTIATE_TEST_CASE_P(GazeboRosDiffDrive, GazeboRosDiffDriveTest, ::testing::Values( +INSTANTIATE_TEST_CASE_P( + GazeboRosDiffDrive, GazeboRosDiffDriveTest, ::testing::Values( TestParams({"worlds/gazebo_ros_diff_drive.world"}), TestParams({"worlds/gazebo_ros_skid_steer_drive.world"}) ), ); diff --git a/gazebo_plugins/test/test_gazebo_ros_gps_sensor.cpp b/gazebo_plugins/test/test_gazebo_ros_gps_sensor.cpp index 386e5b547..7f24a3a38 100644 --- a/gazebo_plugins/test/test_gazebo_ros_gps_sensor.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_gps_sensor.cpp @@ -49,11 +49,11 @@ TEST_F(GazeboRosGpsSensorTest, GpsMessageCorrect) ASSERT_NE(nullptr, node); sensor_msgs::msg::NavSatFix::SharedPtr msg = nullptr; - auto sub = - node->create_subscription("/gps/data", rclcpp::SensorDataQoS(), - [&msg](sensor_msgs::msg::NavSatFix::SharedPtr _msg) { - msg = _msg; - }); + auto sub = node->create_subscription( + "/gps/data", rclcpp::SensorDataQoS(), + [&msg](sensor_msgs::msg::NavSatFix::SharedPtr _msg) { + msg = _msg; + }); world->Step(1); EXPECT_NEAR(0.0, box->WorldPose().Pos().X(), tol); diff --git a/gazebo_plugins/test/test_gazebo_ros_imu_sensor.cpp b/gazebo_plugins/test/test_gazebo_ros_imu_sensor.cpp index e21ca7843..9febde065 100644 --- a/gazebo_plugins/test/test_gazebo_ros_imu_sensor.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_imu_sensor.cpp @@ -48,11 +48,11 @@ TEST_F(GazeboRosImuSensorTest, ImuMessageCorrect) ASSERT_NE(nullptr, node); sensor_msgs::msg::Imu::SharedPtr msg = nullptr; - auto sub = - node->create_subscription("/imu/data", rclcpp::SensorDataQoS(), - [&msg](sensor_msgs::msg::Imu::SharedPtr _msg) { - msg = _msg; - }); + auto sub = node->create_subscription( + "/imu/data", rclcpp::SensorDataQoS(), + [&msg](sensor_msgs::msg::Imu::SharedPtr _msg) { + msg = _msg; + }); // Step until an imu message will have been published int sleep{0}; diff --git a/gazebo_plugins/test/test_gazebo_ros_multicamera.cpp b/gazebo_plugins/test/test_gazebo_ros_multicamera.cpp index d9dbaf4ed..f99bda004 100644 --- a/gazebo_plugins/test/test_gazebo_ros_multicamera.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_multicamera.cpp @@ -57,12 +57,13 @@ TEST_P(GazeboRosMultiCameraTest, CameraSubscribeTest) unsigned int msg_count_left{0}; builtin_interfaces::msg::Time image_stamp_left; - auto sub_left = image_transport::create_subscription(node.get(), GetParam().left_topic, - [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { - image_stamp_left = msg->header.stamp; - ++msg_count_left; - }, - "raw"); + auto sub_left = image_transport::create_subscription( + node.get(), GetParam().left_topic, + [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { + image_stamp_left = msg->header.stamp; + ++msg_count_left; + }, + "raw"); // Update rate is 0.5 Hz, so we step 3s sim time to be sure we get exactly 1 image at 2s world->Step(3000); @@ -81,12 +82,13 @@ TEST_P(GazeboRosMultiCameraTest, CameraSubscribeTest) unsigned int msg_count_right{0}; builtin_interfaces::msg::Time image_stamp_right; - auto sub_right = image_transport::create_subscription(node.get(), GetParam().right_topic, - [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { - image_stamp_right = msg->header.stamp; - ++msg_count_right; - }, - "raw"); + auto sub_right = image_transport::create_subscription( + node.get(), GetParam().right_topic, + [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { + image_stamp_right = msg->header.stamp; + ++msg_count_right; + }, + "raw"); // Update rate is 0.5 Hz, so we step 3s sim time to be sure we get exactly 1 image at 4s world->Step(3000); @@ -104,10 +106,12 @@ TEST_P(GazeboRosMultiCameraTest, CameraSubscribeTest) sub_right.shutdown(); } -INSTANTIATE_TEST_CASE_P(GazeboRosMultiCamera, GazeboRosMultiCameraTest, ::testing::Values( - TestParams({"worlds/gazebo_ros_multicamera.world", - "test_cam/camera/left/image_test", - "test_cam/camera/right/image_test"}) +INSTANTIATE_TEST_CASE_P( + GazeboRosMultiCamera, GazeboRosMultiCameraTest, ::testing::Values( + TestParams( + {"worlds/gazebo_ros_multicamera.world", + "test_cam/camera/left/image_test", + "test_cam/camera/right/image_test"}) ), ); int main(int argc, char ** argv) diff --git a/gazebo_plugins/test/test_gazebo_ros_p3d.cpp b/gazebo_plugins/test/test_gazebo_ros_p3d.cpp index 19ca2c009..c209e98a3 100644 --- a/gazebo_plugins/test/test_gazebo_ros_p3d.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_p3d.cpp @@ -79,11 +79,14 @@ TEST_F(GazeboRosP3dTest, Publishing) EXPECT_EQ("sphere_link", latest_msg->header.frame_id); EXPECT_EQ("box_link", latest_msg->child_frame_id); - EXPECT_NEAR(latest_msg->pose.pose.position.x, + EXPECT_NEAR( + latest_msg->pose.pose.position.x, -ref_link->WorldPose().Pos().X() + link->WorldPose().Pos().X() + 10, tol); - EXPECT_NEAR(latest_msg->pose.pose.position.y, + EXPECT_NEAR( + latest_msg->pose.pose.position.y, -ref_link->WorldPose().Pos().Y() + link->WorldPose().Pos().Y() + 10, tol); - EXPECT_NEAR(latest_msg->pose.pose.position.z, + EXPECT_NEAR( + latest_msg->pose.pose.position.z, -ref_link->WorldPose().Pos().Z() + link->WorldPose().Pos().Z() + 10, tol); EXPECT_NEAR(latest_msg->pose.pose.orientation.x, link->WorldPose().Rot().X(), tol); EXPECT_NEAR(latest_msg->pose.pose.orientation.y, link->WorldPose().Rot().Y(), tol); diff --git a/gazebo_plugins/test/test_gazebo_ros_ray_sensor.cpp b/gazebo_plugins/test/test_gazebo_ros_ray_sensor.cpp index 5fda04d83..36a5a0b25 100644 --- a/gazebo_plugins/test/test_gazebo_ros_ray_sensor.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_ray_sensor.cpp @@ -94,7 +94,8 @@ TEST_F(GazeboRosRaySensorTest, CorrectOutput) // Convienence function to subscribe to a topic and store it to a variable #define SUBSCRIBE_SETTER(msg, topic) \ - node->create_subscription(topic, rclcpp::SensorDataQoS(), \ + node->create_subscription( \ + topic, rclcpp::SensorDataQoS(), \ [&msg](decltype(msg) _msg) { \ msg = _msg; \ }) @@ -167,8 +168,8 @@ TEST_F(GazeboRosRaySensorTest, CorrectOutput) EXPECT_NEAR(ls->angle_max, 0.5236, ROUNDING_ERROR_TOL); EXPECT_NEAR(ls->range_min, 0.05, ROUNDING_ERROR_TOL); EXPECT_NEAR(ls->range_max, 50.0, ROUNDING_ERROR_TOL); - EXPECT_NEAR(ls->angle_increment, (ls->angle_max - ls->angle_min) / ls->ranges.size(), - ROUNDING_ERROR_TOL); + EXPECT_NEAR( + ls->angle_increment, (ls->angle_max - ls->angle_min) / ls->ranges.size(), ROUNDING_ERROR_TOL); // Ensure each ground truth range is found in the laserscan for (size_t i = 0; i < ranges.size(); ++i) { diff --git a/gazebo_plugins/test/test_gazebo_ros_vacuum_gripper.cpp b/gazebo_plugins/test/test_gazebo_ros_vacuum_gripper.cpp index 28fd2da6a..be51624d9 100644 --- a/gazebo_plugins/test/test_gazebo_ros_vacuum_gripper.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_vacuum_gripper.cpp @@ -68,7 +68,8 @@ TEST_F(GazeboRosVacuumGripperTest, VacuumGripperServiceTest) auto request = std::make_shared(); request->data = true; auto response_future = client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); unsigned int sleep = 0; diff --git a/gazebo_plugins/test/test_gazebo_ros_video.cpp b/gazebo_plugins/test/test_gazebo_ros_video.cpp index 6b43b35a4..4ade11fbd 100644 --- a/gazebo_plugins/test/test_gazebo_ros_video.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_video.cpp @@ -99,7 +99,8 @@ TEST_F(GazeboRosVideoTest, VideoSubscribeTest) gazebo::event::Events::postRender(); EXPECT_NE(nullptr, scene->GetVisual("box_display")); - EXPECT_NE(nullptr, scene->GetVisual( + EXPECT_NE( + nullptr, scene->GetVisual( "box_display::base_link::visual::video_visual::display_video_controller")); } } diff --git a/gazebo_ros/include/gazebo_ros/conversions/gazebo_msgs.hpp b/gazebo_ros/include/gazebo_ros/conversions/gazebo_msgs.hpp index f47b15913..56154d3b9 100644 --- a/gazebo_ros/include/gazebo_ros/conversions/gazebo_msgs.hpp +++ b/gazebo_ros/include/gazebo_ros/conversions/gazebo_msgs.hpp @@ -75,14 +75,16 @@ gazebo_msgs::msg::ContactsState Convert(const gazebo::msgs::Contacts & in) // Get force, torque and rotate into user specified frame. // frame_rot is identity if world is used (default for now) - ignition::math::Vector3d force = frame_rot.RotateVectorReverse(ignition::math::Vector3d( - contact.wrench(j).body_1_wrench().force().x(), - contact.wrench(j).body_1_wrench().force().y(), - contact.wrench(j).body_1_wrench().force().z())); - ignition::math::Vector3d torque = frame_rot.RotateVectorReverse(ignition::math::Vector3d( - contact.wrench(j).body_1_wrench().torque().x(), - contact.wrench(j).body_1_wrench().torque().y(), - contact.wrench(j).body_1_wrench().torque().z())); + ignition::math::Vector3d force = frame_rot.RotateVectorReverse( + ignition::math::Vector3d( + contact.wrench(j).body_1_wrench().force().x(), + contact.wrench(j).body_1_wrench().force().y(), + contact.wrench(j).body_1_wrench().force().z())); + ignition::math::Vector3d torque = frame_rot.RotateVectorReverse( + ignition::math::Vector3d( + contact.wrench(j).body_1_wrench().torque().x(), + contact.wrench(j).body_1_wrench().torque().y(), + contact.wrench(j).body_1_wrench().torque().z())); // set wrenches geometry_msgs::msg::Wrench wrench; @@ -99,9 +101,9 @@ gazebo_msgs::msg::ContactsState Convert(const gazebo::msgs::Contacts & in) // transform contact positions into relative frame // set contact positions - ignition::math::Vector3d position = - frame_rot.RotateVectorReverse(ignition::math::Vector3d( - contact.position(j).x(), contact.position(j).y(), contact.position(j).z()) - frame_pos); + ignition::math::Vector3d position = frame_rot.RotateVectorReverse( + ignition::math::Vector3d( + contact.position(j).x(), contact.position(j).y(), contact.position(j).z()) - frame_pos); auto contact_position = Convert(position); @@ -109,9 +111,9 @@ gazebo_msgs::msg::ContactsState Convert(const gazebo::msgs::Contacts & in) // rotate normal into user specified frame. // frame_rot is identity if world is used. - ignition::math::Vector3d normal = - frame_rot.RotateVectorReverse(ignition::math::Vector3d( - contact.normal(j).x(), contact.normal(j).y(), contact.normal(j).z())); + ignition::math::Vector3d normal = frame_rot.RotateVectorReverse( + ignition::math::Vector3d( + contact.normal(j).x(), contact.normal(j).y(), contact.normal(j).z())); // set contact normals auto contact_normal = Convert(normal); state.contact_normals.push_back(contact_normal); diff --git a/gazebo_ros/include/gazebo_ros/conversions/sensor_msgs.hpp b/gazebo_ros/include/gazebo_ros/conversions/sensor_msgs.hpp index 312d3c4d4..8166068d0 100644 --- a/gazebo_ros/include/gazebo_ros/conversions/sensor_msgs.hpp +++ b/gazebo_ros/include/gazebo_ros/conversions/sensor_msgs.hpp @@ -206,7 +206,8 @@ sensor_msgs::msg::PointCloud2 Convert( // Create fields in pointcloud sensor_msgs::PointCloud2Modifier pcd_modifier(pc); - pcd_modifier.setPointCloud2Fields(4, + pcd_modifier.setPointCloud2Fields( + 4, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1, sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32, diff --git a/gazebo_ros/include/gazebo_ros/testing_utils.hpp b/gazebo_ros/include/gazebo_ros/testing_utils.hpp index 377a7478c..df768e932 100644 --- a/gazebo_ros/include/gazebo_ros/testing_utils.hpp +++ b/gazebo_ros/include/gazebo_ros/testing_utils.hpp @@ -131,13 +131,14 @@ get_message_or_timeout( std::atomic_bool msg_received(false); typename T::SharedPtr msg = nullptr; - auto sub = node->create_subscription(topic, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local(), - [&msg_received, &msg](typename T::SharedPtr _msg) { - // If this is the first message from this topic, increment the counter - if (!msg_received.exchange(true)) { - msg = _msg; - } - }); + auto sub = node->create_subscription( + topic, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local(), + [&msg_received, &msg](typename T::SharedPtr _msg) { + // If this is the first message from this topic, increment the counter + if (!msg_received.exchange(true)) { + msg = _msg; + } + }); // Wait for topic to be available using namespace std::literals::chrono_literals; // NOLINT diff --git a/gazebo_ros/src/gazebo_ros_factory.cpp b/gazebo_ros/src/gazebo_ros_factory.cpp index 177757182..801ae886b 100644 --- a/gazebo_ros/src/gazebo_ros_factory.cpp +++ b/gazebo_ros/src/gazebo_ros_factory.cpp @@ -126,12 +126,16 @@ void GazeboRosFactoryPrivate::OnWorldCreated(const std::string & _world_name) // ROS transport ros_node_ = gazebo_ros::Node::Get(); - spawn_service_ = ros_node_->create_service("spawn_entity", - std::bind(&GazeboRosFactoryPrivate::SpawnEntity, this, + spawn_service_ = ros_node_->create_service( + "spawn_entity", + std::bind( + &GazeboRosFactoryPrivate::SpawnEntity, this, std::placeholders::_1, std::placeholders::_2)); - delete_service_ = ros_node_->create_service("delete_entity", - std::bind(&GazeboRosFactoryPrivate::DeleteEntity, this, + delete_service_ = ros_node_->create_service( + "delete_entity", + std::bind( + &GazeboRosFactoryPrivate::DeleteEntity, this, std::placeholders::_1, std::placeholders::_2)); // Gazebo transport @@ -206,7 +210,8 @@ void GazeboRosFactoryPrivate::SpawnEntity( if (req->reference_frame == "" || req->reference_frame == "world" || req->reference_frame == "map" || req->reference_frame == "/map") { - RCLCPP_DEBUG(ros_node_->get_logger(), + RCLCPP_DEBUG( + ros_node_->get_logger(), "SpawnEntity: reference_frame is empty/world/map, using inertial frame"); } else { res->success = false; diff --git a/gazebo_ros/src/gazebo_ros_force_system.cpp b/gazebo_ros/src/gazebo_ros_force_system.cpp index cc8f0aeed..70818635a 100644 --- a/gazebo_ros/src/gazebo_ros_force_system.cpp +++ b/gazebo_ros/src/gazebo_ros_force_system.cpp @@ -172,20 +172,24 @@ void GazeboRosForceSystemPrivate::OnWorldCreated(const std::string & _world_name ros_node_ = gazebo_ros::Node::Get(); apply_link_wrench_service_ = ros_node_->create_service( - "apply_link_wrench", std::bind(&GazeboRosForceSystemPrivate::ApplyLinkWrench, this, - std::placeholders::_1, std::placeholders::_2)); + "apply_link_wrench", std::bind( + &GazeboRosForceSystemPrivate::ApplyLinkWrench, this, + std::placeholders::_1, std::placeholders::_2)); clear_link_wrenches_service_ = ros_node_->create_service( - "clear_link_wrenches", std::bind(&GazeboRosForceSystemPrivate::ClearLinkWrenches, this, - std::placeholders::_1, std::placeholders::_2)); + "clear_link_wrenches", std::bind( + &GazeboRosForceSystemPrivate::ClearLinkWrenches, this, + std::placeholders::_1, std::placeholders::_2)); apply_joint_effort_service_ = ros_node_->create_service( - "apply_joint_effort", std::bind(&GazeboRosForceSystemPrivate::ApplyJointEffort, this, - std::placeholders::_1, std::placeholders::_2)); + "apply_joint_effort", std::bind( + &GazeboRosForceSystemPrivate::ApplyJointEffort, this, + std::placeholders::_1, std::placeholders::_2)); clear_joint_efforts_service_ = ros_node_->create_service( - "clear_joint_efforts", std::bind(&GazeboRosForceSystemPrivate::ClearJointEfforts, this, - std::placeholders::_1, std::placeholders::_2)); + "clear_joint_efforts", std::bind( + &GazeboRosForceSystemPrivate::ClearJointEfforts, this, + std::placeholders::_1, std::placeholders::_2)); } void GazeboRosForceSystemPrivate::TaskExecutor(const gazebo::common::UpdateInfo & _info) @@ -204,7 +208,8 @@ void GazeboRosForceSystemPrivate::TaskExecutor(const gazebo::common::UpdateInfo if (!(*link_wrench_task)->link) { link_wrench_tasks_.erase(link_wrench_task--); - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "Link [%s] does not exist. Deleting task", (*link_wrench_task)->link->GetName().c_str()); } @@ -230,7 +235,8 @@ void GazeboRosForceSystemPrivate::TaskExecutor(const gazebo::common::UpdateInfo if (!(*joint_effort_task)->joint) { joint_effort_tasks_.erase(joint_effort_task--); - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "Joint [%s] does not exist. Deleting task", (*joint_effort_task)->joint->GetName().c_str()); } @@ -288,7 +294,8 @@ void GazeboRosForceSystemPrivate::ApplyLinkWrench( auto target_pose = target_to_ref.Pos(); auto target_rot = target_to_ref.Rot().Euler(); - RCLCPP_DEBUG(ros_node_->get_logger(), + RCLCPP_DEBUG( + ros_node_->get_logger(), "Reference frame for applied wrench:" "[%f %f %f, %f %f %f] - [%f %f %f, %f %f %f] = [%f %f %f, %f %f %f]", link_pose.X(), link_pose.Y(), link_pose.Z(), @@ -301,7 +308,8 @@ void GazeboRosForceSystemPrivate::ApplyLinkWrench( TransformWrench(target_force, target_torque, ref_force, ref_torque, target_to_ref); - RCLCPP_INFO(ros_node_->get_logger(), + RCLCPP_INFO( + ros_node_->get_logger(), "Wrench defined as [%s]:[%f %f %f, %f %f %f] -> Applied as [%s]:[%f %f %f, %f %f %f]", frame->GetName().c_str(), ref_force.X(), ref_force.Y(), ref_force.Z(), @@ -314,7 +322,8 @@ void GazeboRosForceSystemPrivate::ApplyLinkWrench( ignition::math::Pose3d target_to_reference = link->WorldPose(); target_force = ref_force; target_torque = ref_torque; - RCLCPP_INFO(ros_node_->get_logger(), "Reference_frame is empty/world/map," + RCLCPP_INFO( + ros_node_->get_logger(), "Reference_frame is empty/world/map," "using inertial frame, transferring from link relative to inertial frame"); } else { @@ -357,14 +366,17 @@ void GazeboRosForceSystemPrivate::ClearLinkWrenches( { std::lock_guard scoped_lock(lock_); auto prev_end = link_wrench_tasks_.end(); - link_wrench_tasks_.erase(std::remove_if(link_wrench_tasks_.begin(), link_wrench_tasks_.end(), - [_req, this](auto & link_wrench_task) { - if (link_wrench_task->link->GetScopedName() == _req->link_name) { - RCLCPP_INFO(ros_node_->get_logger(), "Deleted wrench on [%s]", _req->link_name.c_str()); - return true; - } - return false; - }), link_wrench_tasks_.end()); + link_wrench_tasks_.erase( + std::remove_if( + link_wrench_tasks_.begin(), link_wrench_tasks_.end(), + [_req, this](auto & link_wrench_task) { + if (link_wrench_task->link->GetScopedName() == _req->link_name) { + RCLCPP_INFO(ros_node_->get_logger(), "Deleted wrench on [%s]", _req->link_name.c_str()); + return true; + } + return false; + }), + link_wrench_tasks_.end()); if (prev_end == link_wrench_tasks_.end()) { RCLCPP_WARN(ros_node_->get_logger(), "No applied wrenches on [%s]", _req->link_name.c_str()); } @@ -403,14 +415,17 @@ void GazeboRosForceSystemPrivate::ClearJointEfforts( { std::lock_guard scoped_lock(lock_); auto prev_end = joint_effort_tasks_.end(); - joint_effort_tasks_.erase(std::remove_if(joint_effort_tasks_.begin(), joint_effort_tasks_.end(), - [_req, this](auto & joint_effort_task) { - if (joint_effort_task->joint->GetName() == _req->joint_name) { - RCLCPP_INFO(ros_node_->get_logger(), "Deleted effort on [%s]", _req->joint_name.c_str()); - return true; - } - return false; - }), joint_effort_tasks_.end()); + joint_effort_tasks_.erase( + std::remove_if( + joint_effort_tasks_.begin(), joint_effort_tasks_.end(), + [_req, this](auto & joint_effort_task) { + if (joint_effort_task->joint->GetName() == _req->joint_name) { + RCLCPP_INFO(ros_node_->get_logger(), "Deleted effort on [%s]", _req->joint_name.c_str()); + return true; + } + return false; + }), + joint_effort_tasks_.end()); if (prev_end == joint_effort_tasks_.end()) { RCLCPP_WARN(ros_node_->get_logger(), "No applied efforts on [%s]", _req->joint_name.c_str()); } diff --git a/gazebo_ros/src/gazebo_ros_init.cpp b/gazebo_ros/src/gazebo_ros_init.cpp index 63e600273..108cee811 100644 --- a/gazebo_ros/src/gazebo_ros_init.cpp +++ b/gazebo_ros/src/gazebo_ros_init.cpp @@ -124,7 +124,8 @@ void GazeboRosInit::Load(int argc, char ** argv) impl_->ros_node_ = gazebo_ros::Node::Get(); } else { impl_->ros_node_ = gazebo_ros::Node::Get(); - RCLCPP_WARN(impl_->ros_node_->get_logger(), + RCLCPP_WARN( + impl_->ros_node_->get_logger(), "gazebo_ros_init didn't initialize ROS " "because it's already initialized with other arguments"); } @@ -157,21 +158,29 @@ void GazeboRosInitPrivate::OnWorldCreated(const std::string & _world_name) world_ = gazebo::physics::get_world(_world_name); // Reset services - reset_simulation_service_ = ros_node_->create_service("reset_simulation", - std::bind(&GazeboRosInitPrivate::OnResetSimulation, this, + reset_simulation_service_ = ros_node_->create_service( + "reset_simulation", + std::bind( + &GazeboRosInitPrivate::OnResetSimulation, this, std::placeholders::_1, std::placeholders::_2)); - reset_world_service_ = ros_node_->create_service("reset_world", - std::bind(&GazeboRosInitPrivate::OnResetWorld, this, + reset_world_service_ = ros_node_->create_service( + "reset_world", + std::bind( + &GazeboRosInitPrivate::OnResetWorld, this, std::placeholders::_1, std::placeholders::_2)); // Pause services - pause_service_ = ros_node_->create_service("pause_physics", - std::bind(&GazeboRosInitPrivate::OnPause, this, + pause_service_ = ros_node_->create_service( + "pause_physics", + std::bind( + &GazeboRosInitPrivate::OnPause, this, std::placeholders::_1, std::placeholders::_2)); - unpause_service_ = ros_node_->create_service("unpause_physics", - std::bind(&GazeboRosInitPrivate::OnUnpause, this, + unpause_service_ = ros_node_->create_service( + "unpause_physics", + std::bind( + &GazeboRosInitPrivate::OnUnpause, this, std::placeholders::_1, std::placeholders::_2)); } diff --git a/gazebo_ros/src/gazebo_ros_state.cpp b/gazebo_ros/src/gazebo_ros_state.cpp index f8c91cf94..b1cc4fd0a 100644 --- a/gazebo_ros/src/gazebo_ros_state.cpp +++ b/gazebo_ros/src/gazebo_ros_state.cpp @@ -99,24 +99,28 @@ void GazeboRosState::Load(gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf impl_->get_entity_state_service_ = impl_->ros_node_->create_service( - "get_entity_state", std::bind(&GazeboRosStatePrivate::GetEntityState, impl_.get(), - std::placeholders::_1, std::placeholders::_2)); + "get_entity_state", std::bind( + &GazeboRosStatePrivate::GetEntityState, impl_.get(), + std::placeholders::_1, std::placeholders::_2)); impl_->set_entity_state_service_ = impl_->ros_node_->create_service( - "set_entity_state", std::bind(&GazeboRosStatePrivate::SetEntityState, impl_.get(), - std::placeholders::_1, std::placeholders::_2)); + "set_entity_state", std::bind( + &GazeboRosStatePrivate::SetEntityState, impl_.get(), + std::placeholders::_1, std::placeholders::_2)); impl_->model_states_pub_ = impl_->ros_node_->create_publisher( "model_states", rclcpp::QoS(rclcpp::KeepLast(1))); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing states of gazebo models at [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing states of gazebo models at [%s]", impl_->model_states_pub_->get_topic_name()); impl_->link_states_pub_ = impl_->ros_node_->create_publisher( "link_states", rclcpp::QoS(rclcpp::KeepLast(1))); - RCLCPP_INFO(impl_->ros_node_->get_logger(), "Publishing states of gazebo links at [%s]", + RCLCPP_INFO( + impl_->ros_node_->get_logger(), "Publishing states of gazebo links at [%s]", impl_->link_states_pub_->get_topic_name()); // Get a callback when world is updated @@ -185,7 +189,8 @@ void GazeboRosStatePrivate::GetEntityState( if (!entity) { _res->success = false; - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "GetEntityState: entity [%s] does not exist", _req->name.c_str()); return; } @@ -207,12 +212,14 @@ void GazeboRosStatePrivate::GetEntityState( entity_lin_vel = frame_pose.Rot().RotateVectorReverse(entity_lin_vel - frame_lin_vel); entity_ang_vel = frame_pose.Rot().RotateVectorReverse(entity_ang_vel - frame_ang_vel); } else if (_req->reference_frame == "" || _req->reference_frame == "world") { - RCLCPP_DEBUG(ros_node_->get_logger(), + RCLCPP_DEBUG( + ros_node_->get_logger(), "GetEntityState: reference_frame is empty/world, using inertial frame"); } else { _res->success = false; - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "GetEntityState: reference entity [%s] not found, did you forget to scope the entity name?", _req->name.c_str()); return; @@ -250,7 +257,8 @@ void GazeboRosStatePrivate::SetEntityState( if (!entity) { _res->success = false; - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "SetEntityState: entity [%s] does not exist", _req->state.name.c_str()); return; } @@ -266,12 +274,14 @@ void GazeboRosStatePrivate::SetEntityState( entity_lin_vel = frame_pose.Rot().RotateVector(entity_lin_vel); entity_ang_vel = frame_pose.Rot().RotateVector(entity_ang_vel); } else if (_req->state.reference_frame == "" || _req->state.reference_frame == "world") { - RCLCPP_DEBUG(ros_node_->get_logger(), + RCLCPP_DEBUG( + ros_node_->get_logger(), "SetEntityState: reference_frame is empty/world, using inertial frame"); } else { _res->success = false; - RCLCPP_ERROR(ros_node_->get_logger(), + RCLCPP_ERROR( + ros_node_->get_logger(), "GetEntityState: reference entity [%s] not found, did you forget to scope the entity name?", _req->state.name.c_str()); return; diff --git a/gazebo_ros/src/node.cpp b/gazebo_ros/src/node.cpp index c073ece60..93803a559 100644 --- a/gazebo_ros/src/node.cpp +++ b/gazebo_ros/src/node.cpp @@ -119,12 +119,14 @@ Node::SharedPtr Node::Get() rclcpp::Parameter Node::sdf_to_ros_parameter(sdf::ElementPtr const & sdf) { if (!sdf->HasAttribute("name")) { - RCLCPP_WARN(internal_logger(), + RCLCPP_WARN( + internal_logger(), "Ignoring parameter because it has no attribute 'name'. Tag: %s", sdf->ToString("").c_str()); return rclcpp::Parameter(); } if (!sdf->HasAttribute("type")) { - RCLCPP_WARN(internal_logger(), + RCLCPP_WARN( + internal_logger(), "Ignoring parameter because it has no attribute 'type'. Tag: %s", sdf->ToString("").c_str()); return rclcpp::Parameter(); } @@ -141,7 +143,8 @@ rclcpp::Parameter Node::sdf_to_ros_parameter(sdf::ElementPtr const & sdf) } else if ("string" == type) { return rclcpp::Parameter(name, sdf->Get()); } else { - RCLCPP_WARN(internal_logger(), + RCLCPP_WARN( + internal_logger(), "Ignoring parameter because attribute 'type' is invalid. Tag: %s", sdf->ToString("").c_str()); return rclcpp::Parameter(); } diff --git a/gazebo_ros/test/plugins/args_init.cpp b/gazebo_ros/test/plugins/args_init.cpp index 92c12556d..27731f5e2 100644 --- a/gazebo_ros/test/plugins/args_init.cpp +++ b/gazebo_ros/test/plugins/args_init.cpp @@ -60,18 +60,19 @@ void ProperInit::Load(int argc, char ** argv) // Run lambda every 1 second using namespace std::chrono_literals; - timer_ = node->create_wall_timer(1s, - [node, pub]() { - // Create string message - auto msg = std_msgs::msg::String(); - msg.data = "Hello world"; - - // Warn with this node's name (to test logging) - RCLCPP_WARN(node->get_logger(), "Publishing"); - - // Publish message - pub->publish(msg); - }); + timer_ = node->create_wall_timer( + 1s, + [node, pub]() { + // Create string message + auto msg = std_msgs::msg::String(); + msg.data = "Hello world"; + + // Warn with this node's name (to test logging) + RCLCPP_WARN(node->get_logger(), "Publishing"); + + // Publish message + pub->publish(msg); + }); } GZ_REGISTER_SYSTEM_PLUGIN(ProperInit) diff --git a/gazebo_ros/test/plugins/create_node_without_init.cpp b/gazebo_ros/test/plugins/create_node_without_init.cpp index a94038138..61c5a7e34 100644 --- a/gazebo_ros/test/plugins/create_node_without_init.cpp +++ b/gazebo_ros/test/plugins/create_node_without_init.cpp @@ -44,18 +44,19 @@ void CreateBeforeInit::Load(int, char **) // Run lambda every 1 second using namespace std::chrono_literals; - timer_ = node->create_wall_timer(1s, - [node, pub]() { - // Create string message - auto msg = std_msgs::msg::String(); - msg.data = "Hello world"; - - // Warn with this node's name (to test logging) - RCLCPP_WARN(node->get_logger(), "Publishing"); - - // Publish message - pub->publish(msg); - }); + timer_ = node->create_wall_timer( + 1s, + [node, pub]() { + // Create string message + auto msg = std_msgs::msg::String(); + msg.data = "Hello world"; + + // Warn with this node's name (to test logging) + RCLCPP_WARN(node->get_logger(), "Publishing"); + + // Publish message + pub->publish(msg); + }); } GZ_REGISTER_SYSTEM_PLUGIN(CreateBeforeInit) diff --git a/gazebo_ros/test/plugins/multiple_nodes.cpp b/gazebo_ros/test/plugins/multiple_nodes.cpp index df3aab7b5..0e78ed8c8 100644 --- a/gazebo_ros/test/plugins/multiple_nodes.cpp +++ b/gazebo_ros/test/plugins/multiple_nodes.cpp @@ -46,28 +46,31 @@ void MultipleNodes::Load(int argc, char ** argv) assert(nullptr != nodeB); // Create publishers - auto pubA = nodeA->create_publisher("testA", - rclcpp::QoS(rclcpp::KeepLast(1)).transient_local()); - auto pubB = nodeB->create_publisher("testB", - rclcpp::QoS(rclcpp::KeepLast(1)).transient_local()); + auto pubA = nodeA->create_publisher( + "testA", + rclcpp::QoS(rclcpp::KeepLast(1)).transient_local()); + auto pubB = nodeB->create_publisher( + "testB", + rclcpp::QoS(rclcpp::KeepLast(1)).transient_local()); // Run lambdas every 1 second using namespace std::chrono_literals; - timer_ = nodeA->create_wall_timer(1s, - [nodeA, nodeB, pubA, pubB]() { - // Create string message - auto msg = std_msgs::msg::String(); - msg.data = "Hello world"; + timer_ = nodeA->create_wall_timer( + 1s, + [nodeA, nodeB, pubA, pubB]() { + // Create string message + auto msg = std_msgs::msg::String(); + msg.data = "Hello world"; - // Warn with this node's name (to test logging) - RCLCPP_WARN(nodeA->get_logger(), "Publishing A"); + // Warn with this node's name (to test logging) + RCLCPP_WARN(nodeA->get_logger(), "Publishing A"); - // Publish message - pubA->publish(msg); + // Publish message + pubA->publish(msg); - RCLCPP_WARN(nodeB->get_logger(), "Publishing B"); - pubB->publish(msg); - }); + RCLCPP_WARN(nodeB->get_logger(), "Publishing B"); + pubB->publish(msg); + }); } GZ_REGISTER_SYSTEM_PLUGIN(MultipleNodes) diff --git a/gazebo_ros/test/plugins/ros_world_plugin.cpp b/gazebo_ros/test/plugins/ros_world_plugin.cpp index f5f76eb79..535a0959c 100644 --- a/gazebo_ros/test/plugins/ros_world_plugin.cpp +++ b/gazebo_ros/test/plugins/ros_world_plugin.cpp @@ -44,18 +44,19 @@ void RosWorldPlugin::Load(gazebo::physics::WorldPtr, sdf::ElementPtr _sdf) // Run lambda every 1 second using namespace std::chrono_literals; - timer_ = node->create_wall_timer(1s, - [node, pub]() { - // Create string message - auto msg = std_msgs::msg::String(); - msg.data = "Hello world, literally"; - - // Warn with this node's name (to test logging) - RCLCPP_WARN(node->get_logger(), "Publishing"); - - // Publish message - pub->publish(msg); - }); + timer_ = node->create_wall_timer( + 1s, + [node, pub]() { + // Create string message + auto msg = std_msgs::msg::String(); + msg.data = "Hello world, literally"; + + // Warn with this node's name (to test logging) + RCLCPP_WARN(node->get_logger(), "Publishing"); + + // Publish message + pub->publish(msg); + }); } GZ_REGISTER_WORLD_PLUGIN(RosWorldPlugin) diff --git a/gazebo_ros/test/plugins/sdf_node.cpp b/gazebo_ros/test/plugins/sdf_node.cpp index 36a6538cc..f1c425bf3 100644 --- a/gazebo_ros/test/plugins/sdf_node.cpp +++ b/gazebo_ros/test/plugins/sdf_node.cpp @@ -117,18 +117,19 @@ void SDFNode::Load(gazebo::physics::WorldPtr, sdf::ElementPtr _sdf) // Run lambda every 1 second using namespace std::chrono_literals; - timer_ = node->create_wall_timer(1s, - [node, pub]() { - // Create string message - auto msg = std_msgs::msg::String(); - msg.data = "Hello world, literally"; - - // Warn with this node's name (to test logging) - RCLCPP_WARN(node->get_logger(), "Publishing"); - - // Publish message - pub->publish(msg); - }); + timer_ = node->create_wall_timer( + 1s, + [node, pub]() { + // Create string message + auto msg = std_msgs::msg::String(); + msg.data = "Hello world, literally"; + + // Warn with this node's name (to test logging) + RCLCPP_WARN(node->get_logger(), "Publishing"); + + // Publish message + pub->publish(msg); + }); } GZ_REGISTER_WORLD_PLUGIN(SDFNode) diff --git a/gazebo_ros/test/test_gazebo_ros_factory.cpp b/gazebo_ros/test/test_gazebo_ros_factory.cpp index 349204f96..48b8fe901 100644 --- a/gazebo_ros/test/test_gazebo_ros_factory.cpp +++ b/gazebo_ros/test/test_gazebo_ros_factory.cpp @@ -71,7 +71,8 @@ TEST_F(GazeboRosFactoryTest, SpawnDelete) ""; auto response_future = spawn_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); auto response = response_future.get(); @@ -115,7 +116,8 @@ TEST_F(GazeboRosFactoryTest, SpawnDelete) ""; auto response_future = spawn_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); auto response = response_future.get(); @@ -131,7 +133,8 @@ TEST_F(GazeboRosFactoryTest, SpawnDelete) // Check it was spawned with the correct name ASSERT_NE(nullptr, world->ModelByName("urdf_box")); - EXPECT_EQ(world->ModelByName("urdf_box")->WorldPose(), + EXPECT_EQ( + world->ModelByName("urdf_box")->WorldPose(), ignition::math::Pose3d(2, 4, 6, 0, 0, 0)); } @@ -152,7 +155,8 @@ TEST_F(GazeboRosFactoryTest, SpawnDelete) ""; auto response_future = spawn_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); auto response = response_future.get(); @@ -161,7 +165,8 @@ TEST_F(GazeboRosFactoryTest, SpawnDelete) // Check it was spawned with the correct name ASSERT_NE(nullptr, world->LightByName("dir")); - EXPECT_EQ(world->LightByName("dir")->WorldPose(), + EXPECT_EQ( + world->LightByName("dir")->WorldPose(), ignition::math::Pose3d(0, 0, 10, 0, 0, 0)); } @@ -175,7 +180,8 @@ TEST_F(GazeboRosFactoryTest, SpawnDelete) request->name = "ground_plane"; auto response_future = delete_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); auto response = response_future.get(); @@ -196,7 +202,8 @@ TEST_F(GazeboRosFactoryTest, SpawnDelete) request->name = "sun"; auto response_future = delete_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); auto response = response_future.get(); diff --git a/gazebo_ros/test/test_gazebo_ros_init.cpp b/gazebo_ros/test/test_gazebo_ros_init.cpp index bcce9b52a..55fe30c50 100644 --- a/gazebo_ros/test/test_gazebo_ros_init.cpp +++ b/gazebo_ros/test/test_gazebo_ros_init.cpp @@ -53,7 +53,8 @@ TEST_F(GazeboRosInitTest, Commands) auto request = std::make_shared(); auto response_future = unpause_physics_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); auto response = response_future.get(); @@ -69,7 +70,8 @@ TEST_F(GazeboRosInitTest, Commands) // Request response_future = pause_physics_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); response = response_future.get(); @@ -97,7 +99,8 @@ TEST_F(GazeboRosInitTest, Commands) auto request = std::make_shared(); auto response_future = reset_simulation_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); auto response = response_future.get(); @@ -123,7 +126,8 @@ TEST_F(GazeboRosInitTest, Commands) request = std::make_shared(); response_future = reset_world_client->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, response_future)); response = response_future.get(); diff --git a/gazebo_ros/test/test_gazebo_ros_joint_effort.cpp b/gazebo_ros/test/test_gazebo_ros_joint_effort.cpp index 4d34e38ca..0b559442f 100644 --- a/gazebo_ros/test/test_gazebo_ros_joint_effort.cpp +++ b/gazebo_ros/test/test_gazebo_ros_joint_effort.cpp @@ -54,7 +54,8 @@ TEST_F(GazeboRosJointEffortTest, JointEffortTest) apply_request->duration = rclcpp::Duration(-1, 0); auto apply_response_future = apply_joint_effort->async_send_request(apply_request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, apply_response_future)); auto apply_response = apply_response_future.get(); @@ -70,7 +71,8 @@ TEST_F(GazeboRosJointEffortTest, JointEffortTest) clear_request->joint_name = "upper_joint"; auto clear_response_future = clear_joint_efforts->async_send_request(clear_request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, clear_response_future)); auto clear_response = clear_response_future.get(); diff --git a/gazebo_ros/test/test_gazebo_ros_link_wrench.cpp b/gazebo_ros/test/test_gazebo_ros_link_wrench.cpp index 677fe089e..9c582b253 100644 --- a/gazebo_ros/test/test_gazebo_ros_link_wrench.cpp +++ b/gazebo_ros/test/test_gazebo_ros_link_wrench.cpp @@ -59,7 +59,8 @@ TEST_F(GazeboRosLinkWrenchTest, LinkWrenchTest) apply_request->duration = rclcpp::Duration(-1, 0); auto apply_response_future = apply_link_wrench->async_send_request(apply_request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, apply_response_future)); auto apply_response = apply_response_future.get(); @@ -80,7 +81,8 @@ TEST_F(GazeboRosLinkWrenchTest, LinkWrenchTest) clear_request->link_name = "box::base"; auto clear_response_future = clear_link_wrenches->async_send_request(clear_request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node, clear_response_future)); auto clear_response = clear_response_future.get(); diff --git a/gazebo_ros/test/test_gazebo_ros_state.cpp b/gazebo_ros/test/test_gazebo_ros_state.cpp index 1ddf23c37..8cc0f653d 100644 --- a/gazebo_ros/test/test_gazebo_ros_state.cpp +++ b/gazebo_ros/test/test_gazebo_ros_state.cpp @@ -95,7 +95,8 @@ void GazeboRosStateTest::GetState( request->name = _entity; auto response_future = get_state_client_->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node_, response_future)); auto response = response_future.get(); @@ -135,7 +136,8 @@ void GazeboRosStateTest::SetState( request->state.twist.angular = gazebo_ros::Convert(_ang_vel); auto response_future = set_state_client_->async_send_request(request); - EXPECT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, + EXPECT_EQ( + rclcpp::executor::FutureReturnCode::SUCCESS, rclcpp::spin_until_future_complete(node_, response_future)); auto response = response_future.get(); @@ -151,11 +153,13 @@ TEST_F(GazeboRosStateTest, GetSet) this->GetState("boxes", ignition::math::Pose3d(0, 0, 0.5, 0, 0, 0)); // Set new state - this->SetState("boxes", ignition::math::Pose3d(1.0, 2.0, 10.0, 0, 0, 0), + this->SetState( + "boxes", ignition::math::Pose3d(1.0, 2.0, 10.0, 0, 0, 0), ignition::math::Vector3d(4.0, 0, 0), ignition::math::Vector3d::Zero); // Check new state - this->GetState("boxes", ignition::math::Pose3d(1.0, 2.0, 10.0, 0, 0, 0), + this->GetState( + "boxes", ignition::math::Pose3d(1.0, 2.0, 10.0, 0, 0, 0), ignition::math::Vector3d(4.0, 0, 0), ignition::math::Vector3d::Zero); } @@ -174,15 +178,18 @@ TEST_F(GazeboRosStateTest, GetSet) // Get / set link state { // Get initial state - note that is was moved with the model - this->GetState("boxes::top", ignition::math::Pose3d(1.0, 2.0, 11.25, 0, 0, 0), + this->GetState( + "boxes::top", ignition::math::Pose3d(1.0, 2.0, 11.25, 0, 0, 0), ignition::math::Vector3d(4.0, 0, 0), ignition::math::Vector3d::Zero); // Set new state - this->SetState("boxes::top", ignition::math::Pose3d(10, 20, 30, 0.1, 0, 0), + this->SetState( + "boxes::top", ignition::math::Pose3d(10, 20, 30, 0.1, 0, 0), ignition::math::Vector3d(1.0, 2.0, 3.0), ignition::math::Vector3d(0.0, 0.0, 4.0)); // Check new state - this->GetState("boxes::top", ignition::math::Pose3d(10, 20, 30, 0.1, 0, 0), + this->GetState( + "boxes::top", ignition::math::Pose3d(10, 20, 30, 0.1, 0, 0), ignition::math::Vector3d(1.0, 2.0, 3.0), ignition::math::Vector3d(0.0, 0.0, 4.0)); } diff --git a/gazebo_ros/test/test_plugins.cpp b/gazebo_ros/test/test_plugins.cpp index 5ad4f2f0d..2c83cc6cd 100644 --- a/gazebo_ros/test/test_plugins.cpp +++ b/gazebo_ros/test/test_plugins.cpp @@ -67,14 +67,17 @@ TEST_P(TestPlugins, TestTopicsReceived) rclcpp::sleep_for(1s); } -INSTANTIATE_TEST_CASE_P(Plugins, TestPlugins, ::testing::Values( +INSTANTIATE_TEST_CASE_P( + Plugins, TestPlugins, ::testing::Values( TestParams({{"-s", "./libargs_init.so"}, {"test"}}), TestParams({{"-s", "./libcreate_node_without_init.so"}, {"test"}}), TestParams({{"-s", "./libmultiple_nodes.so"}, {"testA", "testB"}}), - TestParams({{"-s", "libgazebo_ros_init.so", "worlds/ros_world_plugin.world", - "hello_ros_world:/test:=/new_test"}, {"new_test"}}), - TestParams({{"-s", "libgazebo_ros_init.so", "-s", "libgazebo_ros_factory.so", - "worlds/ros_world_plugin.world"}, {"test"}}), + TestParams( + {{"-s", "libgazebo_ros_init.so", "worlds/ros_world_plugin.world", + "hello_ros_world:/test:=/new_test"}, {"new_test"}}), + TestParams( + {{"-s", "libgazebo_ros_init.so", "-s", "libgazebo_ros_factory.so", + "worlds/ros_world_plugin.world"}, {"test"}}), TestParams({{"-s", "libgazebo_ros_init.so", "worlds/sdf_node_plugin.world"}, {"/foo/my_topic"}}) // cppcheck-suppress syntaxError ), ); diff --git a/gazebo_ros/test/test_sim_time.cpp b/gazebo_ros/test/test_sim_time.cpp index 2b8aa75ca..febf97ccc 100644 --- a/gazebo_ros/test/test_sim_time.cpp +++ b/gazebo_ros/test/test_sim_time.cpp @@ -37,8 +37,8 @@ class TestSimTime : public ::testing::Test void TestSimTime::SetUp() { - gazebo_process_ = std::make_unique(std::vector{"-s", - "libgazebo_ros_init.so"}); + gazebo_process_ = std::make_unique( + std::vector{"-s", "libgazebo_ros_init.so"}); ASSERT_GT(gazebo_process_->Run(), 0); } @@ -61,11 +61,12 @@ TEST_F(TestSimTime, TestClock) std::vector msgs; std::vector times; - auto sub = node->create_subscription("/clock", rclcpp::SystemDefaultsQoS(), - [&](ClockMsg::SharedPtr _msg) { - msgs.push_back(_msg); - times.push_back(node->now()); - }); + auto sub = node->create_subscription( + "/clock", rclcpp::SystemDefaultsQoS(), + [&](ClockMsg::SharedPtr _msg) { + msgs.push_back(_msg); + times.push_back(node->now()); + }); unsigned int sleep{0}; unsigned int max_sleep{30};