diff --git a/available_ros2_types b/available_ros2_types index a3d294bbb..9dfaffbbc 100755 --- a/available_ros2_types +++ b/available_ros2_types @@ -94,6 +94,7 @@ geometry_msgs/TwistWithCovariance.msg geometry_msgs/TwistWithCovarianceStamped.msg geometry_msgs/Vector3.msg geometry_msgs/Vector3Stamped.msg +geometry_msgs/VelocityStamped.msg geometry_msgs/Wrench.msg geometry_msgs/WrenchStamped.msg lifecycle_msgs/ChangeState.srv diff --git a/built_packages b/built_packages index 32305369a..222bff152 100755 --- a/built_packages +++ b/built_packages @@ -16,7 +16,7 @@ https://github.com/micro-ROS/rosidl_typesupport.git 20f4849939c60d46f6e39b3720bb https://github.com/micro-ROS/rosidl_typesupport_microxrcedds.git 7e0331f2ea7329fb05e496a614e7e1f912f6d839 https://github.com/ros-controls/control_msgs 1416954c31432c192ff95a06559847e87386cf60 https://github.com/ros2/ament_cmake_ros.git 60572fa1bec50b9e6fbe64e1b23640d21c15e9d0 -https://github.com/ros2/common_interfaces.git f4eac72f0bbd70f7955a5f709d4a6705eb6ca7e8 +https://github.com/ros2/common_interfaces.git 53761cba9a000902602e7e695cb40de78eadee7f https://github.com/ros2/example_interfaces.git f8deb566a1facf91bd38b9f00c4cf684c5007d85 https://github.com/ros2/libyaml_vendor.git 239f695ceaa0820255f3d0fe02ec8c2bd41b8e78 https://github.com/ros2/rcl.git 619dfb3083bf1121d60767f190eff11ef975e476 diff --git a/src/cortex-m0plus/libmicroros.a b/src/cortex-m0plus/libmicroros.a index 579c48ad8..f70961964 100755 Binary files a/src/cortex-m0plus/libmicroros.a and b/src/cortex-m0plus/libmicroros.a differ diff --git a/src/cortex-m3/libmicroros.a b/src/cortex-m3/libmicroros.a index ef2975eb3..51f04d4d6 100755 Binary files a/src/cortex-m3/libmicroros.a and b/src/cortex-m3/libmicroros.a differ diff --git a/src/cortex-m4/libmicroros.a b/src/cortex-m4/libmicroros.a index 31ecd7f7a..785f764e6 100755 Binary files a/src/cortex-m4/libmicroros.a and b/src/cortex-m4/libmicroros.a differ diff --git a/src/cortex-m7/fpv5-d16-softfp/libmicroros.a b/src/cortex-m7/fpv5-d16-softfp/libmicroros.a index 3f1c4be50..6470fb84b 100755 Binary files a/src/cortex-m7/fpv5-d16-softfp/libmicroros.a and b/src/cortex-m7/fpv5-d16-softfp/libmicroros.a differ diff --git a/src/cortex-m7/fpv5-sp-d16-hardfp/libmicroros.a b/src/cortex-m7/fpv5-sp-d16-hardfp/libmicroros.a index 5436f53ae..1a278f8d5 100755 Binary files a/src/cortex-m7/fpv5-sp-d16-hardfp/libmicroros.a and b/src/cortex-m7/fpv5-sp-d16-hardfp/libmicroros.a differ diff --git a/src/cortex-m7/fpv5-sp-d16-softfp/libmicroros.a b/src/cortex-m7/fpv5-sp-d16-softfp/libmicroros.a index 786db41d3..74991a1e6 100755 Binary files a/src/cortex-m7/fpv5-sp-d16-softfp/libmicroros.a and b/src/cortex-m7/fpv5-sp-d16-softfp/libmicroros.a differ diff --git a/src/esp32/libmicroros.a b/src/esp32/libmicroros.a index 47ad30ead..42190ee68 100755 Binary files a/src/esp32/libmicroros.a and b/src/esp32/libmicroros.a differ diff --git a/src/geometry_msgs/msg/detail/velocity_stamped__functions.h b/src/geometry_msgs/msg/detail/velocity_stamped__functions.h new file mode 100755 index 000000000..c351f8cfe --- /dev/null +++ b/src/geometry_msgs/msg/detail/velocity_stamped__functions.h @@ -0,0 +1,177 @@ +// generated from rosidl_generator_c/resource/idl__functions.h.em +// with input from geometry_msgs:msg/VelocityStamped.idl +// generated code does not contain a copyright notice + +#ifndef GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__FUNCTIONS_H_ +#define GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__FUNCTIONS_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include +#include + +#include "rosidl_runtime_c/visibility_control.h" +#include "geometry_msgs/msg/rosidl_generator_c__visibility_control.h" + +#include "geometry_msgs/msg/detail/velocity_stamped__struct.h" + +/// Initialize msg/VelocityStamped message. +/** + * If the init function is called twice for the same message without + * calling fini inbetween previously allocated memory will be leaked. + * \param[in,out] msg The previously allocated message pointer. + * Fields without a default value will not be initialized by this function. + * You might want to call memset(msg, 0, sizeof( + * geometry_msgs__msg__VelocityStamped + * )) before or use + * geometry_msgs__msg__VelocityStamped__create() + * to allocate and initialize the message. + * \return true if initialization was successful, otherwise false + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +bool +geometry_msgs__msg__VelocityStamped__init(geometry_msgs__msg__VelocityStamped * msg); + +/// Finalize msg/VelocityStamped message. +/** + * \param[in,out] msg The allocated message pointer. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +void +geometry_msgs__msg__VelocityStamped__fini(geometry_msgs__msg__VelocityStamped * msg); + +/// Create msg/VelocityStamped message. +/** + * It allocates the memory for the message, sets the memory to zero, and + * calls + * geometry_msgs__msg__VelocityStamped__init(). + * \return The pointer to the initialized message if successful, + * otherwise NULL + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +geometry_msgs__msg__VelocityStamped * +geometry_msgs__msg__VelocityStamped__create(); + +/// Destroy msg/VelocityStamped message. +/** + * It calls + * geometry_msgs__msg__VelocityStamped__fini() + * and frees the memory of the message. + * \param[in,out] msg The allocated message pointer. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +void +geometry_msgs__msg__VelocityStamped__destroy(geometry_msgs__msg__VelocityStamped * msg); + +/// Check for msg/VelocityStamped message equality. +/** + * \param[in] lhs The message on the left hand size of the equality operator. + * \param[in] rhs The message on the right hand size of the equality operator. + * \return true if messages are equal, otherwise false. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +bool +geometry_msgs__msg__VelocityStamped__are_equal(const geometry_msgs__msg__VelocityStamped * lhs, const geometry_msgs__msg__VelocityStamped * rhs); + +/// Copy a msg/VelocityStamped message. +/** + * This functions performs a deep copy, as opposed to the shallow copy that + * plain assignment yields. + * + * \param[in] input The source message pointer. + * \param[out] output The target message pointer, which must + * have been initialized before calling this function. + * \return true if successful, or false if either pointer is null + * or memory allocation fails. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +bool +geometry_msgs__msg__VelocityStamped__copy( + const geometry_msgs__msg__VelocityStamped * input, + geometry_msgs__msg__VelocityStamped * output); + +/// Initialize array of msg/VelocityStamped messages. +/** + * It allocates the memory for the number of elements and calls + * geometry_msgs__msg__VelocityStamped__init() + * for each element of the array. + * \param[in,out] array The allocated array pointer. + * \param[in] size The size / capacity of the array. + * \return true if initialization was successful, otherwise false + * If the array pointer is valid and the size is zero it is guaranteed + # to return true. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +bool +geometry_msgs__msg__VelocityStamped__Sequence__init(geometry_msgs__msg__VelocityStamped__Sequence * array, size_t size); + +/// Finalize array of msg/VelocityStamped messages. +/** + * It calls + * geometry_msgs__msg__VelocityStamped__fini() + * for each element of the array and frees the memory for the number of + * elements. + * \param[in,out] array The initialized array pointer. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +void +geometry_msgs__msg__VelocityStamped__Sequence__fini(geometry_msgs__msg__VelocityStamped__Sequence * array); + +/// Create array of msg/VelocityStamped messages. +/** + * It allocates the memory for the array and calls + * geometry_msgs__msg__VelocityStamped__Sequence__init(). + * \param[in] size The size / capacity of the array. + * \return The pointer to the initialized array if successful, otherwise NULL + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +geometry_msgs__msg__VelocityStamped__Sequence * +geometry_msgs__msg__VelocityStamped__Sequence__create(size_t size); + +/// Destroy array of msg/VelocityStamped messages. +/** + * It calls + * geometry_msgs__msg__VelocityStamped__Sequence__fini() + * on the array, + * and frees the memory of the array. + * \param[in,out] array The initialized array pointer. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +void +geometry_msgs__msg__VelocityStamped__Sequence__destroy(geometry_msgs__msg__VelocityStamped__Sequence * array); + +/// Check for msg/VelocityStamped message array equality. +/** + * \param[in] lhs The message array on the left hand size of the equality operator. + * \param[in] rhs The message array on the right hand size of the equality operator. + * \return true if message arrays are equal in size and content, otherwise false. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +bool +geometry_msgs__msg__VelocityStamped__Sequence__are_equal(const geometry_msgs__msg__VelocityStamped__Sequence * lhs, const geometry_msgs__msg__VelocityStamped__Sequence * rhs); + +/// Copy an array of msg/VelocityStamped messages. +/** + * This functions performs a deep copy, as opposed to the shallow copy that + * plain assignment yields. + * + * \param[in] input The source array pointer. + * \param[out] output The target array pointer, which must + * have been initialized before calling this function. + * \return true if successful, or false if either pointer + * is null or memory allocation fails. + */ +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +bool +geometry_msgs__msg__VelocityStamped__Sequence__copy( + const geometry_msgs__msg__VelocityStamped__Sequence * input, + geometry_msgs__msg__VelocityStamped__Sequence * output); + +#ifdef __cplusplus +} +#endif + +#endif // GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__FUNCTIONS_H_ diff --git a/src/geometry_msgs/msg/detail/velocity_stamped__rosidl_typesupport_introspection_c.h b/src/geometry_msgs/msg/detail/velocity_stamped__rosidl_typesupport_introspection_c.h new file mode 100755 index 000000000..1bfe489c7 --- /dev/null +++ b/src/geometry_msgs/msg/detail/velocity_stamped__rosidl_typesupport_introspection_c.h @@ -0,0 +1,26 @@ +// generated from rosidl_typesupport_introspection_c/resource/idl__rosidl_typesupport_introspection_c.h.em +// with input from geometry_msgs:msg/VelocityStamped.idl +// generated code does not contain a copyright notice + +#ifndef GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__ROSIDL_TYPESUPPORT_INTROSPECTION_C_H_ +#define GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__ROSIDL_TYPESUPPORT_INTROSPECTION_C_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + + +#include "rosidl_runtime_c/message_type_support_struct.h" +#include "rosidl_typesupport_interface/macros.h" +#include "geometry_msgs/msg/rosidl_typesupport_introspection_c__visibility_control.h" + +ROSIDL_TYPESUPPORT_INTROSPECTION_C_PUBLIC_geometry_msgs +const rosidl_message_type_support_t * +ROSIDL_TYPESUPPORT_INTERFACE__MESSAGE_SYMBOL_NAME(rosidl_typesupport_introspection_c, geometry_msgs, msg, VelocityStamped)(); + +#ifdef __cplusplus +} +#endif + +#endif // GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__ROSIDL_TYPESUPPORT_INTROSPECTION_C_H_ diff --git a/src/geometry_msgs/msg/detail/velocity_stamped__rosidl_typesupport_microxrcedds_c.h b/src/geometry_msgs/msg/detail/velocity_stamped__rosidl_typesupport_microxrcedds_c.h new file mode 100755 index 000000000..350274760 --- /dev/null +++ b/src/geometry_msgs/msg/detail/velocity_stamped__rosidl_typesupport_microxrcedds_c.h @@ -0,0 +1,39 @@ +// generated from rosidl_typesupport_microxrcedds_c/resource/idl__rosidl_typesupport_c.h.em +// with input from geometry_msgs:msg/VelocityStamped.idl +// generated code does not contain a copyright notice +#ifndef GEOMETRY_MSGS__MSG__VELOCITY_STAMPED__ROSIDL_TYPESUPPORT_MICROXRCEDDS_C_H_ +#define GEOMETRY_MSGS__MSG__VELOCITY_STAMPED__ROSIDL_TYPESUPPORT_MICROXRCEDDS_C_H_ + + +#include +#include +#include +#include "rosidl_runtime_c/message_type_support_struct.h" +#include "rosidl_typesupport_interface/macros.h" +#include "geometry_msgs/msg/rosidl_typesupport_microxrcedds_c__visibility_control.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +ROSIDL_TYPESUPPORT_MICROXRCEDDS_C_PUBLIC_geometry_msgs +size_t get_serialized_size_geometry_msgs__msg__VelocityStamped( + const void * untyped_ros_message, + size_t current_alignment); + +ROSIDL_TYPESUPPORT_MICROXRCEDDS_C_PUBLIC_geometry_msgs +size_t max_serialized_size_geometry_msgs__msg__VelocityStamped( + bool * full_bounded, + size_t current_alignment); + +ROSIDL_TYPESUPPORT_MICROXRCEDDS_C_PUBLIC_geometry_msgs +const rosidl_message_type_support_t * + ROSIDL_TYPESUPPORT_INTERFACE__MESSAGE_SYMBOL_NAME(rosidl_typesupport_microxrcedds_c, geometry_msgs, msg, VelocityStamped)(); + +#ifdef __cplusplus +} +#endif + + +#endif // GEOMETRY_MSGS__MSG__VELOCITY_STAMPED__ROSIDL_TYPESUPPORT_MICROXRCEDDS_C_H_ diff --git a/src/geometry_msgs/msg/detail/velocity_stamped__struct.h b/src/geometry_msgs/msg/detail/velocity_stamped__struct.h new file mode 100755 index 000000000..13bca7040 --- /dev/null +++ b/src/geometry_msgs/msg/detail/velocity_stamped__struct.h @@ -0,0 +1,57 @@ +// generated from rosidl_generator_c/resource/idl__struct.h.em +// with input from geometry_msgs:msg/VelocityStamped.idl +// generated code does not contain a copyright notice + +#ifndef GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__STRUCT_H_ +#define GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__STRUCT_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include +#include +#include + + +// Constants defined in the message + +// Include directives for member types +// Member 'header' +#include "std_msgs/msg/detail/header__struct.h" +// Member 'body_frame_id' +// Member 'reference_frame_id' +#include "rosidl_runtime_c/string.h" +// Member 'velocity' +#include "geometry_msgs/msg/detail/twist__struct.h" + +/// Struct defined in msg/VelocityStamped in the package geometry_msgs. +/** + * This expresses the timestamped velocity vector of a frame 'body_frame_id' in the reference frame 'reference_frame_id' expressed from arbitrary observation frame 'header.frame_id'. + * - If the 'body_frame_id' and 'header.frame_id' are identical, the velocity is observed and defined in the local coordinates system of the body + * which is the usual use-case in mobile robotics and is also known as a body twist. + */ +typedef struct geometry_msgs__msg__VelocityStamped +{ + std_msgs__msg__Header header; + rosidl_runtime_c__String body_frame_id; + rosidl_runtime_c__String reference_frame_id; + geometry_msgs__msg__Twist velocity; +} geometry_msgs__msg__VelocityStamped; + +// Struct for a sequence of geometry_msgs__msg__VelocityStamped. +typedef struct geometry_msgs__msg__VelocityStamped__Sequence +{ + geometry_msgs__msg__VelocityStamped * data; + /// The number of valid items in data + size_t size; + /// The number of allocated items in data + size_t capacity; +} geometry_msgs__msg__VelocityStamped__Sequence; + +#ifdef __cplusplus +} +#endif + +#endif // GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__STRUCT_H_ diff --git a/src/geometry_msgs/msg/detail/velocity_stamped__type_support.h b/src/geometry_msgs/msg/detail/velocity_stamped__type_support.h new file mode 100755 index 000000000..b905033c7 --- /dev/null +++ b/src/geometry_msgs/msg/detail/velocity_stamped__type_support.h @@ -0,0 +1,33 @@ +// generated from rosidl_generator_c/resource/idl__type_support.h.em +// with input from geometry_msgs:msg/VelocityStamped.idl +// generated code does not contain a copyright notice + +#ifndef GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__TYPE_SUPPORT_H_ +#define GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__TYPE_SUPPORT_H_ + +#include "rosidl_typesupport_interface/macros.h" + +#include "geometry_msgs/msg/rosidl_generator_c__visibility_control.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rosidl_runtime_c/message_type_support_struct.h" + +// Forward declare the get type support functions for this type. +ROSIDL_GENERATOR_C_PUBLIC_geometry_msgs +const rosidl_message_type_support_t * +ROSIDL_TYPESUPPORT_INTERFACE__MESSAGE_SYMBOL_NAME( + rosidl_typesupport_c, + geometry_msgs, + msg, + VelocityStamped +)(); + +#ifdef __cplusplus +} +#endif + +#endif // GEOMETRY_MSGS__MSG__DETAIL__VELOCITY_STAMPED__TYPE_SUPPORT_H_ diff --git a/src/geometry_msgs/msg/velocity_stamped.h b/src/geometry_msgs/msg/velocity_stamped.h new file mode 100755 index 000000000..b845feeae --- /dev/null +++ b/src/geometry_msgs/msg/velocity_stamped.h @@ -0,0 +1,12 @@ +// generated from rosidl_generator_c/resource/idl.h.em +// with input from geometry_msgs:msg/VelocityStamped.idl +// generated code does not contain a copyright notice + +#ifndef GEOMETRY_MSGS__MSG__VELOCITY_STAMPED_H_ +#define GEOMETRY_MSGS__MSG__VELOCITY_STAMPED_H_ + +#include "geometry_msgs/msg/detail/velocity_stamped__struct.h" +#include "geometry_msgs/msg/detail/velocity_stamped__functions.h" +#include "geometry_msgs/msg/detail/velocity_stamped__type_support.h" + +#endif // GEOMETRY_MSGS__MSG__VELOCITY_STAMPED_H_ diff --git a/src/imxrt1062/fpv5-d16-hard/libmicroros.a b/src/imxrt1062/fpv5-d16-hard/libmicroros.a index 8094d86a9..7b8b4323b 100755 Binary files a/src/imxrt1062/fpv5-d16-hard/libmicroros.a and b/src/imxrt1062/fpv5-d16-hard/libmicroros.a differ diff --git a/src/mk20dx256/libmicroros.a b/src/mk20dx256/libmicroros.a index 6e6cba0c6..d4b348d53 100755 Binary files a/src/mk20dx256/libmicroros.a and b/src/mk20dx256/libmicroros.a differ diff --git a/src/mk64fx512/fpv4-sp-d16-hard/libmicroros.a b/src/mk64fx512/fpv4-sp-d16-hard/libmicroros.a index b33cabdd5..d8681ee8f 100755 Binary files a/src/mk64fx512/fpv4-sp-d16-hard/libmicroros.a and b/src/mk64fx512/fpv4-sp-d16-hard/libmicroros.a differ diff --git a/src/mk66fx1m0/fpv4-sp-d16-hard/libmicroros.a b/src/mk66fx1m0/fpv4-sp-d16-hard/libmicroros.a index b33cabdd5..d8681ee8f 100755 Binary files a/src/mk66fx1m0/fpv4-sp-d16-hard/libmicroros.a and b/src/mk66fx1m0/fpv4-sp-d16-hard/libmicroros.a differ