Skip to content

Commit c754417

Browse files
authored
Merge branch 'rolling' into new-win-bin-install
2 parents a64a706 + f08a6f9 commit c754417

28 files changed

+507
-86
lines changed

source/Concepts.rst

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,3 @@ Related Content
1515
^^^^^^^^^^^^^^^
1616

1717
:doc:`See the ROS 2 citations <Citations>` for more explanation of concepts and citable resources.
18-
19-
For a brief video introduction to ROS 2, see this community contributed content:
20-
21-
* `Getting started with ROS Part 1: Nodes, Parameters and Topics <https://youtu.be/46TPAKXBOF8>`_
22-
* `Getting started with ROS Part 2: Services and Actions <https://youtu.be/keZAJ83eEoM>`_

source/Concepts/Intermediate/About-RQt.rst

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,3 @@ Further Reading
8181
* ROS 2 Discourse `announcement of porting to ROS 2 <https://discourse.ros.org/t/rqt-in-ros2/6428>`__)
8282
* `RQt for ROS 1 documentation <https://wiki.ros.org/rqt>`__
8383
* Brief overview of RQt (from `a Willow Garage intern blog post <http://web.archive.org/web/20130518142837/http://www.willowgarage.com/blog/2012/10/21/ros-gui>`__)
84-
85-
.. raw:: html
86-
87-
<iframe width="560" height="315" src="https://www.youtube-nocookie.com/embed/CyP9wHu2PpY" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>

source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,7 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c
9494

9595
writer_->open("my_bag");
9696

97-
auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
97+
auto subscription_callback_lambda = [this](std::shared_ptr<const rclcpp::SerializedMessage> msg){
9898
rclcpp::Time time_stamp = this->now();
9999

100100
writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
@@ -144,7 +144,7 @@ We will write data to the bag in the callback.
144144

145145
.. code-block:: C++
146146

147-
auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
147+
auto subscription_callback_lambda = [this](std::shared_ptr<const rclcpp::SerializedMessage> msg){
148148
rclcpp::Time time_stamp = this->now();
149149

150150
writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
@@ -162,7 +162,7 @@ We do this for two reasons.
162162

163163
.. code-block:: C++
164164

165-
auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
165+
auto subscription_callback_lambda = [this](std::shared_ptr<const rclcpp::SerializedMessage> msg){
166166

167167
Within the subscription callback, the first thing to do is determine the time stamp to use for the stored message.
168168
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.

source/Tutorials/Advanced/Simulators/Webots/Code/MyRobotDriver.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ void MyRobotDriver::init(
2525

2626
cmd_vel_subscription_ = node->create_subscription<geometry_msgs::msg::Twist>(
2727
"/cmd_vel", rclcpp::SensorDataQoS().reliable(),
28-
[this](const geometry_msgs::msg::Twist::SharedPtr msg){
28+
[this](const geometry_msgs::msg::Twist::ConstSharedPtr msg){
2929
this->cmd_vel_msg.linear = msg->linear;
3030
this->cmd_vel_msg.angular = msg->angular;
3131
}

source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -7,26 +7,26 @@ ObstacleAvoider::ObstacleAvoider() : Node("obstacle_avoider") {
77

88
left_sensor_sub_ = create_subscription<sensor_msgs::msg::Range>(
99
"/left_sensor", 1,
10-
[this](const sensor_msgs::msg::Range::SharedPtr msg){
10+
[this](const sensor_msgs::msg::Range::ConstSharedPtr msg){
1111
return this->leftSensorCallback(msg);
1212
}
1313
);
1414

1515
right_sensor_sub_ = create_subscription<sensor_msgs::msg::Range>(
1616
"/right_sensor", 1,
17-
[this](const sensor_msgs::msg::Range::SharedPtr msg){
17+
[this](const sensor_msgs::msg::Range::ConstSharedPtr msg){
1818
return this->rightSensorCallback(msg);
1919
}
2020
);
2121
}
2222

2323
void ObstacleAvoider::leftSensorCallback(
24-
const sensor_msgs::msg::Range::SharedPtr msg) {
24+
const sensor_msgs::msg::Range::ConstSharedPtr msg) {
2525
left_sensor_value = msg->range;
2626
}
2727

2828
void ObstacleAvoider::rightSensorCallback(
29-
const sensor_msgs::msg::Range::SharedPtr msg) {
29+
const sensor_msgs::msg::Range::ConstSharedPtr msg) {
3030
right_sensor_value = msg->range;
3131

3232
auto command_message = std::make_unique<geometry_msgs::msg::Twist>();

source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,8 @@ class ObstacleAvoider : public rclcpp::Node {
99
explicit ObstacleAvoider();
1010

1111
private:
12-
void leftSensorCallback(const sensor_msgs::msg::Range::SharedPtr msg);
13-
void rightSensorCallback(const sensor_msgs::msg::Range::SharedPtr msg);
12+
void leftSensorCallback(const sensor_msgs::msg::Range::ConstSharedPtr msg);
13+
void rightSensorCallback(const sensor_msgs::msg::Range::ConstSharedPtr msg);
1414

1515
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
1616
rclcpp::Subscription<sensor_msgs::msg::Range>::SharedPtr left_sensor_sub_;

source/Tutorials/Beginner-CLI-Tools/Introducing-Turtlesim/Introducing-Turtlesim.rst

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -263,5 +263,3 @@ Related content
263263
---------------
264264

265265
The turtlesim package can be found in the `ros_tutorials <https://github.com/ros/ros_tutorials/tree/{REPOS_FILE_BRANCH}/turtlesim>`_ repo.
266-
267-
`This community contributed video <https://youtu.be/xwT7XWflMdc>`_ demonstrates many of the items covered in this tutorial.

source/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.rst

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -184,9 +184,11 @@ This allows the installed files to be changed by changing the files in the ``sou
184184

185185
.. code-block:: console
186186
187-
$ colcon build --symlink-install --merge-install
187+
$ colcon build --merge-install
188188
189189
Windows doesn't allow long paths, so ``merge-install`` will combine all the paths into the ``install`` directory.
190+
On Windows, you need special permissions to create symbolic links, so ``--symlink-install`` is not used by default.
191+
To use it, you need to run the command as administrator or enable developer mode in system settings.
190192

191193
.. tip::
192194

0 commit comments

Comments
 (0)