diff --git a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst index 34c83cfda08..f2ff5282c48 100644 --- a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst +++ b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst @@ -94,7 +94,7 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c writer_->open("my_bag"); - auto subscription_callback_lambda = [this](std::shared_ptr msg){ + auto subscription_callback_lambda = [this](std::shared_ptr msg){ rclcpp::Time time_stamp = this->now(); writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp); @@ -144,7 +144,7 @@ We will write data to the bag in the callback. .. code-block:: C++ - auto subscription_callback_lambda = [this](std::shared_ptr msg){ + auto subscription_callback_lambda = [this](std::shared_ptr msg){ rclcpp::Time time_stamp = this->now(); writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp); @@ -162,7 +162,7 @@ We do this for two reasons. .. code-block:: C++ - auto subscription_callback_lambda = [this](std::shared_ptr msg){ + auto subscription_callback_lambda = [this](std::shared_ptr msg){ Within the subscription callback, the first thing to do is determine the time stamp to use for the stored message. This can be anything appropriate to your data, but two common values are the time at which the data was produced, if known, and the time it is received. diff --git a/source/Tutorials/Advanced/Simulators/Webots/Code/MyRobotDriver.cpp b/source/Tutorials/Advanced/Simulators/Webots/Code/MyRobotDriver.cpp index dab1253033a..4a929764205 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Code/MyRobotDriver.cpp +++ b/source/Tutorials/Advanced/Simulators/Webots/Code/MyRobotDriver.cpp @@ -25,7 +25,7 @@ void MyRobotDriver::init( cmd_vel_subscription_ = node->create_subscription( "/cmd_vel", rclcpp::SensorDataQoS().reliable(), - [this](const geometry_msgs::msg::Twist::SharedPtr msg){ + [this](const geometry_msgs::msg::Twist::ConstSharedPtr msg){ this->cmd_vel_msg.linear = msg->linear; this->cmd_vel_msg.angular = msg->angular; } diff --git a/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.cpp b/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.cpp index 530f4baa192..e00e922a09f 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.cpp +++ b/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.cpp @@ -7,26 +7,26 @@ ObstacleAvoider::ObstacleAvoider() : Node("obstacle_avoider") { left_sensor_sub_ = create_subscription( "/left_sensor", 1, - [this](const sensor_msgs::msg::Range::SharedPtr msg){ + [this](const sensor_msgs::msg::Range::ConstSharedPtr msg){ return this->leftSensorCallback(msg); } ); right_sensor_sub_ = create_subscription( "/right_sensor", 1, - [this](const sensor_msgs::msg::Range::SharedPtr msg){ + [this](const sensor_msgs::msg::Range::ConstSharedPtr msg){ return this->rightSensorCallback(msg); } ); } void ObstacleAvoider::leftSensorCallback( - const sensor_msgs::msg::Range::SharedPtr msg) { + const sensor_msgs::msg::Range::ConstSharedPtr msg) { left_sensor_value = msg->range; } void ObstacleAvoider::rightSensorCallback( - const sensor_msgs::msg::Range::SharedPtr msg) { + const sensor_msgs::msg::Range::ConstSharedPtr msg) { right_sensor_value = msg->range; auto command_message = std::make_unique(); diff --git a/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.hpp b/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.hpp index 51c2b3e8703..61838aaaed9 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.hpp +++ b/source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.hpp @@ -9,8 +9,8 @@ class ObstacleAvoider : public rclcpp::Node { explicit ObstacleAvoider(); private: - void leftSensorCallback(const sensor_msgs::msg::Range::SharedPtr msg); - void rightSensorCallback(const sensor_msgs::msg::Range::SharedPtr msg); + void leftSensorCallback(const sensor_msgs::msg::Range::ConstSharedPtr msg); + void rightSensorCallback(const sensor_msgs::msg::Range::ConstSharedPtr msg); rclcpp::Publisher::SharedPtr publisher_; rclcpp::Subscription::SharedPtr left_sensor_sub_; diff --git a/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst b/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst index a988ead3231..59ca1ae8ebc 100644 --- a/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst +++ b/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Broadcaster-Cpp.rst @@ -101,7 +101,7 @@ Open the file using your preferred text editor. stream << "/" << turtlename_.c_str() << "/pose"; std::string topic_name = stream.str(); - auto handle_turtle_pose = [this](const std::shared_ptr msg){ + auto handle_turtle_pose = [this](const std::shared_ptr msg){ geometry_msgs::msg::TransformStamped t; // Read message content and assign it to