Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c
}

private:
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
void topic_callback(std::shared_ptr<const rclcpp::SerializedMessage> msg) const
{
rclcpp::Time time_stamp = this->now();

Expand Down Expand Up @@ -158,7 +158,7 @@ We do this for two reasons.

.. code-block:: C++

void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
void topic_callback(std::shared_ptr<const rclcpp::SerializedMessage> msg) const
{

Within the subscription callback, the first thing to do is determine the time stamp to use for the stored message.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ void MyRobotDriver::init(
}

void MyRobotDriver::cmdVelCallback(
const geometry_msgs::msg::Twist::SharedPtr msg) {
const geometry_msgs::msg::Twist::ConstSharedPtr msg) {
cmd_vel_msg.linear = msg->linear;
cmd_vel_msg.angular = msg->angular;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,12 @@ ObstacleAvoider::ObstacleAvoider() : Node("obstacle_avoider") {
}

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<geometry_msgs::msg::Twist>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<geometry_msgs::msg::Twist>::SharedPtr publisher_;
rclcpp::Subscription<sensor_msgs::msg::Range>::SharedPtr left_sensor_sub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ Open the file using your preferred text editor.
}

private:
void handle_turtle_pose(const std::shared_ptr<turtlesim::msg::Pose> msg)
void handle_turtle_pose(const std::shared_ptr<const turtlesim::msg::Pose> msg)
{
geometry_msgs::msg::TransformStamped t;

Expand Down