Skip to content

Commit 89ea3f0

Browse files
micro-ROS rolling Library auto-update 10-04-2022 06:19 (#929)
Co-authored-by: pablogs9 <[email protected]>
1 parent 971c6aa commit 89ea3f0

File tree

16 files changed

+74
-65
lines changed

16 files changed

+74
-65
lines changed

built_packages

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
https://github.com/ament/ament_cmake.git 2bf27ce5ad01af340e1f4efd44232c1067d0dbda
33
https://github.com/ament/ament_package.git f8ea958fd02cff6f4192425e28566369c92b5e34
44
https://github.com/ament/uncrustify_vendor.git ec8f8b4d03483671e8ea2b3039f1015f92b0ef89
5-
https://github.com/ament/ament_lint.git 4d23cd104004d25a72969a395b7de5bae0fb0e7e
5+
https://github.com/ament/ament_lint.git 88f424dca6c85b597756a83f871c118862a6992a
66
https://github.com/ament/googletest.git 6df7425fdcbd368d2d1b99ffd89b9168014abb07
77
https://github.com/ament/ament_index.git f019d6c40991799a13b18c9c3dcc583e3fde0381
88
https://github.com/ros2/ament_cmake_ros.git 60572fa1bec50b9e6fbe64e1b23640d21c15e9d0
@@ -11,7 +11,7 @@ https://github.com/ros2/common_interfaces.git f3cb4848560e91596e7688e8ac1816828f
1111
https://github.com/ros2/rosidl_defaults.git 1f1ee2a6169837b10302ffb2a52fb2f2a57239b2
1212
https://github.com/ros2/rcl.git 24ad44e984ad36be2be818d558bc0710329a5da7
1313
https://github.com/ros2/unique_identifier_msgs.git 27767cefcf8a80da44641dc208c57722c28aa11c
14-
https://github.com/ros2/rosidl.git 7909d0f66109482c28a118472431670bdcecf622
14+
https://github.com/ros2/rosidl.git de0556a13be36ca62d6a6573da369e3fe2eb204c
1515
https://github.com/ros2/test_interface_files.git a0c8f5e338490ddf8b98238dce35c06810115e8b
1616
https://github.com/ros2/rosidl_dds.git ab8497770c652edb40d6b1591118198cbcf14237
1717
https://github.com/ros2/rcl_logging.git e9e2c3515cf4099a4369a4da1cea257f99384f49
@@ -25,7 +25,7 @@ https://github.com/eProsima/Micro-XRCE-DDS-Client.git 9b9278c0b3a633aa7ad634bda2
2525
https://github.com/eProsima/Micro-CDR.git cb4403a8780095df94a7b1936b1e00153c90070d
2626
https://github.com/yaml/libyaml.git 2c891fc7a770e8ba2fec34fc6b545c672beb37e6
2727
https://github.com/micro-ROS/rcl 067ef1effe7ada177ffa1fc3b58237eaceb0699c
28-
https://github.com/ros2/rclc 56ee3c12187043443b72f412c7fa90c714784fd9
28+
https://github.com/ros2/rclc 79a2df204ff8f745539d842cf669fadd1dd4ca7e
2929
https://github.com/micro-ROS/rosidl_typesupport_microxrcedds.git 28b88ac044e504095fbe9381508925e0aec7bc24
3030
https://github.com/micro-ROS/rcutils 342c39ce7cbc3d90ea1d4552ddcbb45ae14bec6d
3131
https://github.com/micro-ROS/rosidl_typesupport.git 0a28c7b07241b2f287c5f6f8090eb6a92cb4519f

src/actionlib_msgs/msg/detail/goal_status__struct.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ enum
3838
/// Constant 'PREEMPTED'.
3939
/**
4040
* The goal received a cancel request after it started executing
41-
* and has since completed its execution (Terminal State).
41+
* and has since completed its execution (Terminal State).
4242
*/
4343
enum
4444
{
@@ -48,7 +48,7 @@ enum
4848
/// Constant 'SUCCEEDED'.
4949
/**
5050
* The goal was achieved successfully by the action server
51-
* (Terminal State).
51+
* (Terminal State).
5252
*/
5353
enum
5454
{
@@ -88,7 +88,7 @@ enum
8888
/// Constant 'RECALLING'.
8989
/**
9090
* The goal received a cancel request before it started executing, but
91-
* the action server has not yet confirmed that the goal is canceled.
91+
* the action server has not yet confirmed that the goal is canceled.
9292
*/
9393
enum
9494
{
@@ -98,7 +98,7 @@ enum
9898
/// Constant 'RECALLED'.
9999
/**
100100
* The goal received a cancel request before it started executing
101-
* and was successfully cancelled (Terminal State).
101+
* and was successfully cancelled (Terminal State).
102102
*/
103103
enum
104104
{
@@ -108,7 +108,7 @@ enum
108108
/// Constant 'LOST'.
109109
/**
110110
* An action client can determine that a goal is LOST. This should not
111-
* be sent over the wire by an action server.
111+
* be sent over the wire by an action server.
112112
*/
113113
enum
114114
{

src/control_msgs/action/detail/follow_joint_trajectory__struct.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -124,9 +124,9 @@ typedef struct control_msgs__action__FollowJointTrajectory_Result
124124
/// - INVALID_GOAL: The reason for the invalid goal (e.g., the requested
125125
/// trajectory is in the past).
126126
/// - INVALID_JOINTS: The mismatch between the expected controller joints
127-
/// and those provided in the goal.
127+
/// and those provided in the goal.
128128
/// - PATH_TOLERANCE_VIOLATED and GOAL_TOLERANCE_VIOLATED: Which joint
129-
/// violated which tolerance, and by how much.
129+
/// violated which tolerance, and by how much.
130130
rosidl_runtime_c__String error_string;
131131
} control_msgs__action__FollowJointTrajectory_Result;
132132

src/control_msgs/msg/detail/joint_tolerance__struct.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,9 @@ extern "C"
3030
* abort.
3131
*
3232
* There are two special values for tolerances:
33-
* * 0 - The tolerance is unspecified and will remain at whatever the default is
34-
* * -1 - The tolerance is "erased". If there was a default, the joint will be
35-
* allowed to move without restriction.
33+
* * 0 - The tolerance is unspecified and will remain at whatever the default is
34+
* * -1 - The tolerance is "erased". If there was a default, the joint will be
35+
* allowed to move without restriction.
3636
*/
3737
typedef struct control_msgs__msg__JointTolerance
3838
{

src/geometry_msgs/msg/detail/inertia__struct.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ typedef struct geometry_msgs__msg__Inertia
3333
/// Inertia Tensor
3434
/// | ixx ixy ixz |
3535
/// I = | ixy iyy iyz |
36-
/// | ixz iyz izz |
36+
/// | ixz iyz izz |
3737
double ixx;
3838
double ixy;
3939
double ixz;

src/rclc_lifecycle/rclc_lifecycle.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,11 @@
1717
#ifndef RCLC_LIFECYCLE__RCLC_LIFECYCLE_H_
1818
#define RCLC_LIFECYCLE__RCLC_LIFECYCLE_H_
1919

20+
#if __cplusplus
21+
extern "C"
22+
{
23+
#endif
24+
2025
#define RCLC_LIFECYCLE_MAX_NUMBER_OF_STATES 100 // highest transition id: 99
2126

2227
#include <rcutils/logging_macros.h>
@@ -157,4 +162,8 @@ rclc_lifecycle_node_fini(
157162
rclc_lifecycle_node_t * node,
158163
rcl_allocator_t * allocator);
159164

165+
#if __cplusplus
166+
}
167+
#endif
168+
160169
#endif // RCLC_LIFECYCLE__RCLC_LIFECYCLE_H_

src/sensor_msgs/msg/detail/camera_info__struct.h

Lines changed: 24 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -33,11 +33,11 @@ extern "C"
3333
* camera namespace on topic "camera_info" and accompanied by up to five
3434
* image topics named:
3535
*
36-
* image_raw - raw data from the camera driver, possibly Bayer encoded
36+
* image_raw - raw data from the camera driver, possibly Bayer encoded
3737
* image - monochrome, distorted
38-
* image_color - color, distorted
39-
* image_rect - monochrome, rectified
40-
* image_rect_color - color, rectified
38+
* image_color - color, distorted
39+
* image_rect - monochrome, rectified
40+
* image_rect_color - color, rectified
4141
*
4242
* The image_pipeline contains packages (image_proc, stereo_image_proc)
4343
* for producing the four processed image topics from image_raw and
@@ -65,16 +65,16 @@ typedef struct sensor_msgs__msg__CameraInfo
6565
/// +y should point down in the image
6666
/// +z should point into the plane of the image
6767
std_msgs__msg__Header header;
68-
/// Calibration Parameters #
68+
/// Calibration Parameters #
6969
///
7070
/// These are fixed during camera calibration. Their values will be the #
7171
/// same in all messages until the camera is recalibrated. Note that #
7272
/// self-calibrating systems may "recalibrate" frequently. #
73-
/// #
73+
/// #
7474
/// The internal parameters can be used to warp a raw (distorted) image #
7575
/// to: #
76-
/// 1. An undistorted image (requires D and K) #
77-
/// 2. A rectified image (requires D, K, R) #
76+
/// 1. An undistorted image (requires D and K) #
77+
/// 2. A rectified image (requires D, K, R) #
7878
/// The projection matrix P projects 3D points into the rectified image.#
7979
///
8080
/// The image dimensions with which the camera was calibrated.
@@ -106,47 +106,47 @@ typedef struct sensor_msgs__msg__CameraInfo
106106
/// Projection/camera matrix
107107
/// [fx' 0 cx' Tx]
108108
/// P = [ 0 fy' cy' Ty]
109-
/// [ 0 0 1 0]
109+
/// [ 0 0 1 0]
110110
/// By convention, this matrix specifies the intrinsic (camera) matrix
111-
/// of the processed (rectified) image. That is, the left 3x3 portion
112-
/// is the normal camera intrinsic matrix for the rectified image.
111+
/// of the processed (rectified) image. That is, the left 3x3 portion
112+
/// is the normal camera intrinsic matrix for the rectified image.
113113
/// It projects 3D points in the camera coordinate frame to 2D pixel
114114
/// coordinates using the focal lengths (fx', fy') and principal point
115-
/// (cx', cy') - these may differ from the values in K.
115+
/// (cx', cy') - these may differ from the values in K.
116116
/// For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
117117
/// also have R = the identity and P[1:3,1:3] = K.
118118
/// For a stereo pair, the fourth column [Tx Ty 0]' is related to the
119119
/// position of the optical center of the second camera in the first
120-
/// camera's frame. We assume Tz = 0 so both cameras are in the same
121-
/// stereo image plane. The first camera always has Tx = Ty = 0. For
122-
/// the right (second) camera of a horizontal stereo pair, Ty = 0 and
123-
/// Tx = -fx' * B, where B is the baseline between the cameras.
120+
/// camera's frame. We assume Tz = 0 so both cameras are in the same
121+
/// stereo image plane. The first camera always has Tx = Ty = 0. For
122+
/// the right (second) camera of a horizontal stereo pair, Ty = 0 and
123+
/// Tx = -fx' * B, where B is the baseline between the cameras.
124124
/// Given a 3D point [X Y Z]', the projection (x, y) of the point onto
125-
/// the rectified image is given by:
126-
/// [u v w]' = P * [X Y Z 1]'
125+
/// the rectified image is given by:
126+
/// [u v w]' = P * [X Y Z 1]'
127127
/// x = u / w
128-
/// y = v / w
128+
/// y = v / w
129129
/// This holds for both images of a stereo pair.
130130
/// 3x4 row-major matrix
131131
double p[12];
132-
/// Operational Parameters #
132+
/// Operational Parameters #
133133
///
134134
/// These define the image region actually captured by the camera #
135135
/// driver. Although they affect the geometry of the output image, they #
136136
/// may be changed freely without recalibrating the camera. #
137137
///
138138
/// Binning refers here to any camera setting which combines rectangular
139-
/// neighborhoods of pixels into larger "super-pixels." It reduces the
140-
/// resolution of the output image to
139+
/// neighborhoods of pixels into larger "super-pixels." It reduces the
140+
/// resolution of the output image to
141141
/// (width / binning_x) x (height / binning_y).
142142
/// The default values binning_x = binning_y = 0 is considered the same
143143
/// as binning_x = binning_y = 1 (no subsampling).
144144
uint32_t binning_x;
145145
uint32_t binning_y;
146146
/// Region of interest (subwindow of full camera resolution), given in
147147
/// full resolution (unbinned) image coordinates. A particular ROI
148-
/// always denotes the same window of pixels on the camera sensor,
149-
/// regardless of binning settings.
148+
/// always denotes the same window of pixels on the camera sensor,
149+
/// regardless of binning settings.
150150
/// The default setting of roi (all values 0) is considered the same as
151151
/// full resolution (roi.width = width, roi.height = height).
152152
sensor_msgs__msg__RegionOfInterest roi;

src/sensor_msgs/msg/detail/channel_float32__struct.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -32,15 +32,15 @@ extern "C"
3232
* point.
3333
*
3434
* Channel names in existing practice include:
35-
* "u", "v" - row and column (respectively) in the left stereo image.
36-
* This is opposite to usual conventions but remains for
37-
* historical reasons. The newer PointCloud2 message has no
35+
* "u", "v" - row and column (respectively) in the left stereo image.
36+
* This is opposite to usual conventions but remains for
37+
* historical reasons. The newer PointCloud2 message has no
3838
* such problem.
3939
* "rgb" - For point clouds produced by color stereo cameras. uint8
40-
* (R,G,B) values packed into the least significant 24 bits,
40+
* (R,G,B) values packed into the least significant 24 bits,
4141
* in order.
4242
* "intensity" - laser or pixel intensity.
43-
* "distance"
43+
* "distance"
4444
*/
4545
typedef struct sensor_msgs__msg__ChannelFloat32
4646
{

src/sensor_msgs/msg/detail/joint_state__struct.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,8 @@ extern "C"
3232
* This is a message that holds data to describe the state of a set of torque controlled joints.
3333
*
3434
* The state of each joint (revolute or prismatic) is defined by:
35-
* * the position of the joint (rad or m),
36-
* * the velocity of the joint (rad/s or m/s) and
35+
* * the position of the joint (rad or m),
36+
* * the velocity of the joint (rad/s or m/s) and
3737
* * the effort that is applied in the joint (Nm or N).
3838
*
3939
* Each joint is uniquely identified by its name

src/sensor_msgs/msg/detail/nav_sat_fix__struct.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -62,13 +62,13 @@ enum
6262
typedef struct sensor_msgs__msg__NavSatFix
6363
{
6464
/// header.stamp specifies the ROS time for this measurement (the
65-
/// corresponding satellite time may be reported using the
66-
/// sensor_msgs/TimeReference message).
65+
/// corresponding satellite time may be reported using the
66+
/// sensor_msgs/TimeReference message).
6767
///
6868
/// header.frame_id is the frame of reference reported by the satellite
6969
/// receiver, usually the location of the antenna. This is a
70-
/// Euclidean frame relative to the vehicle, not a reference
71-
/// ellipsoid.
70+
/// Euclidean frame relative to the vehicle, not a reference
71+
/// ellipsoid.
7272
std_msgs__msg__Header header;
7373
/// Satellite fix status information.
7474
sensor_msgs__msg__NavSatStatus status;

0 commit comments

Comments
 (0)