From b9b60f0ee25b4ed3bfe34b3ceef3b9d07e122996 Mon Sep 17 00:00:00 2001 From: William Lew Date: Mon, 8 Nov 2021 15:10:52 -0800 Subject: [PATCH 01/15] Added Light and Color messages Signed-off-by: William Lew --- .../include/ros_ign_bridge/convert.hpp | 28 ++ .../include/ros_ign_interfaces/msg/color.hpp | 11 + .../msg/detail/color__builder.hpp | 103 +++++ .../msg/detail/color__struct.hpp | 172 ++++++++ .../msg/detail/color__traits.hpp | 96 +++++ .../msg/detail/light__builder.hpp | 311 +++++++++++++++ .../msg/detail/light__struct.hpp | 375 ++++++++++++++++++ .../msg/detail/light__traits.hpp | 231 +++++++++++ .../include/ros_ign_interfaces/msg/light.hpp | 11 + ros_ign_bridge/src/convert.cpp | 96 +++++ ros_ign_bridge/src/factories.cpp | 69 ++++ ros_ign_bridge/src/factories.hpp | 40 ++ ros_ign_interfaces/CMakeLists.txt | 2 + ros_ign_interfaces/msg/Color.msg | 4 + ros_ign_interfaces/msg/Light.msg | 27 ++ 15 files changed, 1576 insertions(+) create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp create mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp create mode 100644 ros_ign_interfaces/msg/Color.msg create mode 100644 ros_ign_interfaces/msg/Light.msg diff --git a/ros_ign_bridge/include/ros_ign_bridge/convert.hpp b/ros_ign_bridge/include/ros_ign_bridge/convert.hpp index 6da7e239..740c9253 100644 --- a/ros_ign_bridge/include/ros_ign_bridge/convert.hpp +++ b/ros_ign_bridge/include/ros_ign_bridge/convert.hpp @@ -50,9 +50,37 @@ #include +#include +#include + namespace ros_ign_bridge { +// ros_ign_interfaces +template<> +void +convert_ros_to_ign( + const ros_ign_interfaces::msg::Color & ros_msg, + ignition::msgs::Color & ign_msg); + +template<> +void +convert_ign_to_ros( + const ignition::msgs::Color & ign_msg, + ros_ign_interfaces::msg::Color & ros_msg); + +template<> +void +convert_ros_to_ign( + const ros_ign_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & ign_msg); + +template<> +void +convert_ign_to_ros( + const ignition::msgs::Light & ign_msg, + ros_ign_interfaces::msg::Light & ros_msg); + // std_msgs template<> void diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp new file mode 100644 index 00000000..fd893af1 --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp @@ -0,0 +1,11 @@ +// generated from rosidl_generator_cpp/resource/idl.hpp.em +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__COLOR_HPP_ +#define ROS_IGN_INTERFACES__COLOR_HPP_ + +#include "ros_ign_interfaces/msg/detail/color__struct.hpp" +#include "ros_ign_interfaces/msg/detail/color__builder.hpp" +#include "ros_ign_interfaces/msg/detail/color__traits.hpp" + +#endif // ROS_IGN_INTERFACES__COLOR_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp new file mode 100644 index 00000000..6dbdab3b --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp @@ -0,0 +1,103 @@ +// generated from rosidl_generator_cpp/resource/idl__builder.hpp.em +// with input from ros_ign_interfaces:Color.idl +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__DETAIL__COLOR__BUILDER_HPP_ +#define ROS_IGN_INTERFACES__DETAIL__COLOR__BUILDER_HPP_ + +#include "ros_ign_interfaces/msg/detail/color__struct.hpp" +#include +#include +#include + + +namespace ros_ign_interfaces +{ + +namespace msg +{ + +namespace builder +{ + +class Init_Color_a +{ +public: + explicit Init_Color_a(::ros_ign_interfaces::msg::Color & msg) + : msg_(msg) + {} + ::ros_ign_interfaces::msg::Color a(::ros_ign_interfaces::msg::Color::_a_type arg) + { + msg_.a = std::move(arg); + return std::move(msg_); + } + +private: + ::ros_ign_interfaces::msg::Color msg_; +}; + +class Init_Color_b +{ +public: + explicit Init_Color_b(::ros_ign_interfaces::msg::Color & msg) + : msg_(msg) + {} + Init_Color_a b(::ros_ign_interfaces::msg::Color::_b_type arg) + { + msg_.b = std::move(arg); + return Init_Color_a(msg_); + } + +private: + ::ros_ign_interfaces::msg::Color msg_; +}; + +class Init_Color_g +{ +public: + explicit Init_Color_g(::ros_ign_interfaces::msg::Color & msg) + : msg_(msg) + {} + Init_Color_b g(::ros_ign_interfaces::msg::Color::_g_type arg) + { + msg_.g = std::move(arg); + return Init_Color_b(msg_); + } + +private: + ::ros_ign_interfaces::msg::Color msg_; +}; + +class Init_Color_r +{ +public: + Init_Color_r() + : msg_(::rosidl_runtime_cpp::MessageInitialization::SKIP) + {} + Init_Color_g r(::ros_ign_interfaces::msg::Color::_r_type arg) + { + msg_.r = std::move(arg); + return Init_Color_g(msg_); + } + +private: + ::ros_ign_interfaces::msg::Color msg_; +}; + +} // namespace builder + +} // namespace msg + +template +auto build(); + +template<> +inline +auto build<::ros_ign_interfaces::msg::Color>() +{ + return ros_ign_interfaces::msg::builder::Init_Color_r(); +} + +} // namespace ros_ign_interfaces + +#endif // ROS_IGN_INTERFACES__DETAIL__COLOR__BUILDER_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp new file mode 100644 index 00000000..545a5af4 --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp @@ -0,0 +1,172 @@ +// generated from rosidl_generator_cpp/resource/idl__struct.hpp.em +// with input from ros_ign_interfaces:Color.idl +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__DETAIL__COLOR__STRUCT_HPP_ +#define ROS_IGN_INTERFACES__DETAIL__COLOR__STRUCT_HPP_ + +#include +#include +#include +#include +#include +#include +#include + + +#ifndef _WIN32 +# define DEPRECATED__ros_ign_interfaces__Color __attribute__((deprecated)) +#else +# define DEPRECATED__ros_ign_interfaces__Color __declspec(deprecated) +#endif + +namespace ros_ign_interfaces +{ + +namespace msg +{ + +// message struct +template +struct Color_ +{ + using Type = Color_; + + explicit Color_(rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) + { + if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || + rosidl_runtime_cpp::MessageInitialization::ZERO == _init) + { + this->r = 0.0f; + this->g = 0.0f; + this->b = 0.0f; + this->a = 0.0f; + } + } + + explicit Color_(const ContainerAllocator & _alloc, rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) + { + (void)_alloc; + if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || + rosidl_runtime_cpp::MessageInitialization::ZERO == _init) + { + this->r = 0.0f; + this->g = 0.0f; + this->b = 0.0f; + this->a = 0.0f; + } + } + + // field types and members + using _r_type = + float; + _r_type r; + using _g_type = + float; + _g_type g; + using _b_type = + float; + _b_type b; + using _a_type = + float; + _a_type a; + + // setters for named parameter idiom + Type & set__r( + const float & _arg) + { + this->r = _arg; + return *this; + } + Type & set__g( + const float & _arg) + { + this->g = _arg; + return *this; + } + Type & set__b( + const float & _arg) + { + this->b = _arg; + return *this; + } + Type & set__a( + const float & _arg) + { + this->a = _arg; + return *this; + } + + // constant declarations + + // pointer types + using RawPtr = + ros_ign_interfaces::msg::Color_ *; + using ConstRawPtr = + const ros_ign_interfaces::msg::Color_ *; + using SharedPtr = + std::shared_ptr>; + using ConstSharedPtr = + std::shared_ptr const>; + + template>> + using UniquePtrWithDeleter = + std::unique_ptr, Deleter>; + + using UniquePtr = UniquePtrWithDeleter<>; + + template>> + using ConstUniquePtrWithDeleter = + std::unique_ptr const, Deleter>; + using ConstUniquePtr = ConstUniquePtrWithDeleter<>; + + using WeakPtr = + std::weak_ptr>; + using ConstWeakPtr = + std::weak_ptr const>; + + // pointer types similar to ROS 1, use SharedPtr / ConstSharedPtr instead + // NOTE: Can't use 'using' here because GNU C++ can't parse attributes properly + typedef DEPRECATED__ros_ign_interfaces__Color + std::shared_ptr> + Ptr; + typedef DEPRECATED__ros_ign_interfaces__Color + std::shared_ptr const> + ConstPtr; + + // comparison operators + bool operator==(const Color_ & other) const + { + if (this->r != other.r) { + return false; + } + if (this->g != other.g) { + return false; + } + if (this->b != other.b) { + return false; + } + if (this->a != other.a) { + return false; + } + return true; + } + bool operator!=(const Color_ & other) const + { + return !this->operator==(other); + } +}; // struct Color_ + +// alias to use template instance with default allocator +using Color = + ros_ign_interfaces::msg::Color_>; + +// constant definitions + +} // namespace msg + +} // namespace ros_ign_interfaces + +#endif // ROS_IGN_INTERFACES__DETAIL__COLOR__STRUCT_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp new file mode 100644 index 00000000..04ea5b2b --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp @@ -0,0 +1,96 @@ +// generated from rosidl_generator_cpp/resource/idl__traits.hpp.em +// with input from ros_ign_interfaces:Color.idl +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__DETAIL__COLOR__TRAITS_HPP_ +#define ROS_IGN_INTERFACES__DETAIL__COLOR__TRAITS_HPP_ + +#include "ros_ign_interfaces/msg/detail/color__struct.hpp" +#include +#include +#include +#include +#include + +namespace rosidl_generator_traits +{ + +inline void to_yaml( + const ros_ign_interfaces::msg::Color & msg, + std::ostream & out, size_t indentation = 0) +{ + // member: r + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "r: "; + value_to_yaml(msg.r, out); + out << "\n"; + } + + // member: g + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "g: "; + value_to_yaml(msg.g, out); + out << "\n"; + } + + // member: b + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "b: "; + value_to_yaml(msg.b, out); + out << "\n"; + } + + // member: a + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "a: "; + value_to_yaml(msg.a, out); + out << "\n"; + } +} // NOLINT(readability/fn_size) + +inline std::string to_yaml(const ros_ign_interfaces::msg::Color & msg) +{ + std::ostringstream out; + to_yaml(msg, out); + return out.str(); +} + +template<> +inline const char * data_type() +{ + return "ros_ign_interfaces::msg::Color"; +} + +template<> +inline const char * name() +{ + return "ros_ign_interfaces/msg/Color"; +} + +template<> +struct has_fixed_size + : std::integral_constant {}; + +template<> +struct has_bounded_size + : std::integral_constant {}; + +template<> +struct is_message + : std::true_type {}; + +} // namespace rosidl_generator_traits + +#endif // ROS_IGN_INTERFACES__DETAIL__COLOR__TRAITS_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp new file mode 100644 index 00000000..005763cb --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp @@ -0,0 +1,311 @@ +// generated from rosidl_generator_cpp/resource/idl__builder.hpp.em +// with input from ros_ign_interfaces:Light.idl +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__DETAIL__LIGHT__BUILDER_HPP_ +#define ROS_IGN_INTERFACES__DETAIL__LIGHT__BUILDER_HPP_ + +#include "ros_ign_interfaces/msg/detail/light__struct.hpp" +#include +#include +#include + + +namespace ros_ign_interfaces +{ + +namespace msg +{ + +namespace builder +{ + +class Init_Light_intensity +{ +public: + explicit Init_Light_intensity(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + ::ros_ign_interfaces::msg::Light intensity(::ros_ign_interfaces::msg::Light::_intensity_type arg) + { + msg_.intensity = std::move(arg); + return std::move(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_parent_id +{ +public: + explicit Init_Light_parent_id(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_intensity parent_id(::ros_ign_interfaces::msg::Light::_parent_id_type arg) + { + msg_.parent_id = std::move(arg); + return Init_Light_intensity(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_id +{ +public: + explicit Init_Light_id(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_parent_id id(::ros_ign_interfaces::msg::Light::_id_type arg) + { + msg_.id = std::move(arg); + return Init_Light_parent_id(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_spot_falloff +{ +public: + explicit Init_Light_spot_falloff(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_id spot_falloff(::ros_ign_interfaces::msg::Light::_spot_falloff_type arg) + { + msg_.spot_falloff = std::move(arg); + return Init_Light_id(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_spot_outer_angle +{ +public: + explicit Init_Light_spot_outer_angle(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_spot_falloff spot_outer_angle(::ros_ign_interfaces::msg::Light::_spot_outer_angle_type arg) + { + msg_.spot_outer_angle = std::move(arg); + return Init_Light_spot_falloff(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_spot_inner_angle +{ +public: + explicit Init_Light_spot_inner_angle(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_spot_outer_angle spot_inner_angle(::ros_ign_interfaces::msg::Light::_spot_inner_angle_type arg) + { + msg_.spot_inner_angle = std::move(arg); + return Init_Light_spot_outer_angle(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_cast_shadows +{ +public: + explicit Init_Light_cast_shadows(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_spot_inner_angle cast_shadows(::ros_ign_interfaces::msg::Light::_cast_shadows_type arg) + { + msg_.cast_shadows = std::move(arg); + return Init_Light_spot_inner_angle(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_range +{ +public: + explicit Init_Light_range(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_cast_shadows range(::ros_ign_interfaces::msg::Light::_range_type arg) + { + msg_.range = std::move(arg); + return Init_Light_cast_shadows(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_direction +{ +public: + explicit Init_Light_direction(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_range direction(::ros_ign_interfaces::msg::Light::_direction_type arg) + { + msg_.direction = std::move(arg); + return Init_Light_range(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_attenuation_quadratic +{ +public: + explicit Init_Light_attenuation_quadratic(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_direction attenuation_quadratic(::ros_ign_interfaces::msg::Light::_attenuation_quadratic_type arg) + { + msg_.attenuation_quadratic = std::move(arg); + return Init_Light_direction(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_attenuation_linear +{ +public: + explicit Init_Light_attenuation_linear(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_attenuation_quadratic attenuation_linear(::ros_ign_interfaces::msg::Light::_attenuation_linear_type arg) + { + msg_.attenuation_linear = std::move(arg); + return Init_Light_attenuation_quadratic(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_attenuation_constant +{ +public: + explicit Init_Light_attenuation_constant(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_attenuation_linear attenuation_constant(::ros_ign_interfaces::msg::Light::_attenuation_constant_type arg) + { + msg_.attenuation_constant = std::move(arg); + return Init_Light_attenuation_linear(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_specular +{ +public: + explicit Init_Light_specular(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_attenuation_constant specular(::ros_ign_interfaces::msg::Light::_specular_type arg) + { + msg_.specular = std::move(arg); + return Init_Light_attenuation_constant(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_diffuse +{ +public: + explicit Init_Light_diffuse(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_specular diffuse(::ros_ign_interfaces::msg::Light::_diffuse_type arg) + { + msg_.diffuse = std::move(arg); + return Init_Light_specular(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_pose +{ +public: + explicit Init_Light_pose(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_diffuse pose(::ros_ign_interfaces::msg::Light::_pose_type arg) + { + msg_.pose = std::move(arg); + return Init_Light_diffuse(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_type +{ +public: + explicit Init_Light_type(::ros_ign_interfaces::msg::Light & msg) + : msg_(msg) + {} + Init_Light_pose type(::ros_ign_interfaces::msg::Light::_type_type arg) + { + msg_.type = std::move(arg); + return Init_Light_pose(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +class Init_Light_name +{ +public: + Init_Light_name() + : msg_(::rosidl_runtime_cpp::MessageInitialization::SKIP) + {} + Init_Light_type name(::ros_ign_interfaces::msg::Light::_name_type arg) + { + msg_.name = std::move(arg); + return Init_Light_type(msg_); + } + +private: + ::ros_ign_interfaces::msg::Light msg_; +}; + +} // namespace builder + +} // namespace msg + +template +auto build(); + +template<> +inline +auto build<::ros_ign_interfaces::msg::Light>() +{ + return ros_ign_interfaces::msg::builder::Init_Light_name(); +} + +} // namespace ros_ign_interfaces + +#endif // ROS_IGN_INTERFACES__DETAIL__LIGHT__BUILDER_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp new file mode 100644 index 00000000..8f4561ca --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp @@ -0,0 +1,375 @@ +// generated from rosidl_generator_cpp/resource/idl__struct.hpp.em +// with input from ros_ign_interfaces:Light.idl +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__DETAIL__LIGHT__STRUCT_HPP_ +#define ROS_IGN_INTERFACES__DETAIL__LIGHT__STRUCT_HPP_ + +#include +#include +#include +#include +#include +#include +#include + + +// Include directives for member types +// Member 'pose' +#include "geometry_msgs/msg/detail/pose__struct.hpp" +// Member 'diffuse' +// Member 'specular' +#include "ros_ign_interfaces/msg/detail/color__struct.hpp" +// Member 'direction' +#include "geometry_msgs/msg/detail/vector3__struct.hpp" + +#ifndef _WIN32 +# define DEPRECATED__ros_ign_interfaces__Light __attribute__((deprecated)) +#else +# define DEPRECATED__ros_ign_interfaces__Light __declspec(deprecated) +#endif + +namespace ros_ign_interfaces +{ + +namespace msg +{ + +// message struct +template +struct Light_ +{ + using Type = Light_; + + explicit Light_(rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) + : pose(_init), + diffuse(_init), + specular(_init), + direction(_init) + { + if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || + rosidl_runtime_cpp::MessageInitialization::ZERO == _init) + { + this->name = ""; + this->type = 0; + this->attenuation_constant = 0.0f; + this->attenuation_linear = 0.0f; + this->attenuation_quadratic = 0.0f; + this->range = 0.0f; + this->cast_shadows = false; + this->spot_inner_angle = 0.0f; + this->spot_outer_angle = 0.0f; + this->spot_falloff = 0.0f; + this->id = 0ul; + this->parent_id = 0ul; + this->intensity = 0.0f; + } + } + + explicit Light_(const ContainerAllocator & _alloc, rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) + : name(_alloc), + pose(_alloc, _init), + diffuse(_alloc, _init), + specular(_alloc, _init), + direction(_alloc, _init) + { + if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || + rosidl_runtime_cpp::MessageInitialization::ZERO == _init) + { + this->name = ""; + this->type = 0; + this->attenuation_constant = 0.0f; + this->attenuation_linear = 0.0f; + this->attenuation_quadratic = 0.0f; + this->range = 0.0f; + this->cast_shadows = false; + this->spot_inner_angle = 0.0f; + this->spot_outer_angle = 0.0f; + this->spot_falloff = 0.0f; + this->id = 0ul; + this->parent_id = 0ul; + this->intensity = 0.0f; + } + } + + // field types and members + using _name_type = + std::basic_string, typename std::allocator_traits::template rebind_alloc>; + _name_type name; + using _type_type = + uint8_t; + _type_type type; + using _pose_type = + geometry_msgs::msg::Pose_; + _pose_type pose; + using _diffuse_type = + ros_ign_interfaces::msg::Color_; + _diffuse_type diffuse; + using _specular_type = + ros_ign_interfaces::msg::Color_; + _specular_type specular; + using _attenuation_constant_type = + float; + _attenuation_constant_type attenuation_constant; + using _attenuation_linear_type = + float; + _attenuation_linear_type attenuation_linear; + using _attenuation_quadratic_type = + float; + _attenuation_quadratic_type attenuation_quadratic; + using _direction_type = + geometry_msgs::msg::Vector3_; + _direction_type direction; + using _range_type = + float; + _range_type range; + using _cast_shadows_type = + bool; + _cast_shadows_type cast_shadows; + using _spot_inner_angle_type = + float; + _spot_inner_angle_type spot_inner_angle; + using _spot_outer_angle_type = + float; + _spot_outer_angle_type spot_outer_angle; + using _spot_falloff_type = + float; + _spot_falloff_type spot_falloff; + using _id_type = + uint32_t; + _id_type id; + using _parent_id_type = + uint32_t; + _parent_id_type parent_id; + using _intensity_type = + float; + _intensity_type intensity; + + // setters for named parameter idiom + Type & set__name( + const std::basic_string, typename std::allocator_traits::template rebind_alloc> & _arg) + { + this->name = _arg; + return *this; + } + Type & set__type( + const uint8_t & _arg) + { + this->type = _arg; + return *this; + } + Type & set__pose( + const geometry_msgs::msg::Pose_ & _arg) + { + this->pose = _arg; + return *this; + } + Type & set__diffuse( + const ros_ign_interfaces::msg::Color_ & _arg) + { + this->diffuse = _arg; + return *this; + } + Type & set__specular( + const ros_ign_interfaces::msg::Color_ & _arg) + { + this->specular = _arg; + return *this; + } + Type & set__attenuation_constant( + const float & _arg) + { + this->attenuation_constant = _arg; + return *this; + } + Type & set__attenuation_linear( + const float & _arg) + { + this->attenuation_linear = _arg; + return *this; + } + Type & set__attenuation_quadratic( + const float & _arg) + { + this->attenuation_quadratic = _arg; + return *this; + } + Type & set__direction( + const geometry_msgs::msg::Vector3_ & _arg) + { + this->direction = _arg; + return *this; + } + Type & set__range( + const float & _arg) + { + this->range = _arg; + return *this; + } + Type & set__cast_shadows( + const bool & _arg) + { + this->cast_shadows = _arg; + return *this; + } + Type & set__spot_inner_angle( + const float & _arg) + { + this->spot_inner_angle = _arg; + return *this; + } + Type & set__spot_outer_angle( + const float & _arg) + { + this->spot_outer_angle = _arg; + return *this; + } + Type & set__spot_falloff( + const float & _arg) + { + this->spot_falloff = _arg; + return *this; + } + Type & set__id( + const uint32_t & _arg) + { + this->id = _arg; + return *this; + } + Type & set__parent_id( + const uint32_t & _arg) + { + this->parent_id = _arg; + return *this; + } + Type & set__intensity( + const float & _arg) + { + this->intensity = _arg; + return *this; + } + + // constant declarations + static constexpr uint8_t POINT = + 0u; + static constexpr uint8_t SPOT = + 1u; + static constexpr uint8_t DIRECTIONAL = + 2u; + + // pointer types + using RawPtr = + ros_ign_interfaces::msg::Light_ *; + using ConstRawPtr = + const ros_ign_interfaces::msg::Light_ *; + using SharedPtr = + std::shared_ptr>; + using ConstSharedPtr = + std::shared_ptr const>; + + template>> + using UniquePtrWithDeleter = + std::unique_ptr, Deleter>; + + using UniquePtr = UniquePtrWithDeleter<>; + + template>> + using ConstUniquePtrWithDeleter = + std::unique_ptr const, Deleter>; + using ConstUniquePtr = ConstUniquePtrWithDeleter<>; + + using WeakPtr = + std::weak_ptr>; + using ConstWeakPtr = + std::weak_ptr const>; + + // pointer types similar to ROS 1, use SharedPtr / ConstSharedPtr instead + // NOTE: Can't use 'using' here because GNU C++ can't parse attributes properly + typedef DEPRECATED__ros_ign_interfaces__Light + std::shared_ptr> + Ptr; + typedef DEPRECATED__ros_ign_interfaces__Light + std::shared_ptr const> + ConstPtr; + + // comparison operators + bool operator==(const Light_ & other) const + { + if (this->name != other.name) { + return false; + } + if (this->type != other.type) { + return false; + } + if (this->pose != other.pose) { + return false; + } + if (this->diffuse != other.diffuse) { + return false; + } + if (this->specular != other.specular) { + return false; + } + if (this->attenuation_constant != other.attenuation_constant) { + return false; + } + if (this->attenuation_linear != other.attenuation_linear) { + return false; + } + if (this->attenuation_quadratic != other.attenuation_quadratic) { + return false; + } + if (this->direction != other.direction) { + return false; + } + if (this->range != other.range) { + return false; + } + if (this->cast_shadows != other.cast_shadows) { + return false; + } + if (this->spot_inner_angle != other.spot_inner_angle) { + return false; + } + if (this->spot_outer_angle != other.spot_outer_angle) { + return false; + } + if (this->spot_falloff != other.spot_falloff) { + return false; + } + if (this->id != other.id) { + return false; + } + if (this->parent_id != other.parent_id) { + return false; + } + if (this->intensity != other.intensity) { + return false; + } + return true; + } + bool operator!=(const Light_ & other) const + { + return !this->operator==(other); + } +}; // struct Light_ + +// alias to use template instance with default allocator +using Light = + ros_ign_interfaces::msg::Light_>; + +// constant definitions +template +constexpr uint8_t Light_::POINT; +template +constexpr uint8_t Light_::SPOT; +template +constexpr uint8_t Light_::DIRECTIONAL; + +} // namespace msg + +} // namespace ros_ign_interfaces + +#endif // ROS_IGN_INTERFACES__DETAIL__LIGHT__STRUCT_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp new file mode 100644 index 00000000..7ef94e76 --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp @@ -0,0 +1,231 @@ +// generated from rosidl_generator_cpp/resource/idl__traits.hpp.em +// with input from ros_ign_interfaces:Light.idl +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__DETAIL__LIGHT__TRAITS_HPP_ +#define ROS_IGN_INTERFACES__DETAIL__LIGHT__TRAITS_HPP_ + +#include "ros_ign_interfaces/msg/detail/light__struct.hpp" +#include +#include +#include +#include +#include + +// Include directives for member types +// Member 'pose' +#include "geometry_msgs/msg/detail/pose__traits.hpp" +// Member 'diffuse' +// Member 'specular' +#include "ros_ign_interfaces/msg/detail/color__traits.hpp" +// Member 'direction' +#include "geometry_msgs/msg/detail/vector3__traits.hpp" + +namespace rosidl_generator_traits +{ + +inline void to_yaml( + const ros_ign_interfaces::msg::Light & msg, + std::ostream & out, size_t indentation = 0) +{ + // member: name + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "name: "; + value_to_yaml(msg.name, out); + out << "\n"; + } + + // member: type + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "type: "; + value_to_yaml(msg.type, out); + out << "\n"; + } + + // member: pose + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "pose:\n"; + to_yaml(msg.pose, out, indentation + 2); + } + + // member: diffuse + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "diffuse:\n"; + to_yaml(msg.diffuse, out, indentation + 2); + } + + // member: specular + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "specular:\n"; + to_yaml(msg.specular, out, indentation + 2); + } + + // member: attenuation_constant + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "attenuation_constant: "; + value_to_yaml(msg.attenuation_constant, out); + out << "\n"; + } + + // member: attenuation_linear + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "attenuation_linear: "; + value_to_yaml(msg.attenuation_linear, out); + out << "\n"; + } + + // member: attenuation_quadratic + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "attenuation_quadratic: "; + value_to_yaml(msg.attenuation_quadratic, out); + out << "\n"; + } + + // member: direction + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "direction:\n"; + to_yaml(msg.direction, out, indentation + 2); + } + + // member: range + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "range: "; + value_to_yaml(msg.range, out); + out << "\n"; + } + + // member: cast_shadows + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "cast_shadows: "; + value_to_yaml(msg.cast_shadows, out); + out << "\n"; + } + + // member: spot_inner_angle + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "spot_inner_angle: "; + value_to_yaml(msg.spot_inner_angle, out); + out << "\n"; + } + + // member: spot_outer_angle + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "spot_outer_angle: "; + value_to_yaml(msg.spot_outer_angle, out); + out << "\n"; + } + + // member: spot_falloff + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "spot_falloff: "; + value_to_yaml(msg.spot_falloff, out); + out << "\n"; + } + + // member: id + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "id: "; + value_to_yaml(msg.id, out); + out << "\n"; + } + + // member: parent_id + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "parent_id: "; + value_to_yaml(msg.parent_id, out); + out << "\n"; + } + + // member: intensity + { + if (indentation > 0) { + out << std::string(indentation, ' '); + } + out << "intensity: "; + value_to_yaml(msg.intensity, out); + out << "\n"; + } +} // NOLINT(readability/fn_size) + +inline std::string to_yaml(const ros_ign_interfaces::msg::Light & msg) +{ + std::ostringstream out; + to_yaml(msg, out); + return out.str(); +} + +template<> +inline const char * data_type() +{ + return "ros_ign_interfaces::msg::Light"; +} + +template<> +inline const char * name() +{ + return "ros_ign_interfaces/msg/Light"; +} + +template<> +struct has_fixed_size + : std::integral_constant {}; + +template<> +struct has_bounded_size + : std::integral_constant {}; + +template<> +struct is_message + : std::true_type {}; + +} // namespace rosidl_generator_traits + +#endif // ROS_IGN_INTERFACES__DETAIL__LIGHT__TRAITS_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp new file mode 100644 index 00000000..cac4d304 --- /dev/null +++ b/ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp @@ -0,0 +1,11 @@ +// generated from rosidl_generator_cpp/resource/idl.hpp.em +// generated code does not contain a copyright notice + +#ifndef ROS_IGN_INTERFACES__LIGHT_HPP_ +#define ROS_IGN_INTERFACES__LIGHT_HPP_ + +#include "ros_ign_interfaces/msg/detail/light__struct.hpp" +#include "ros_ign_interfaces/msg/detail/light__builder.hpp" +#include "ros_ign_interfaces/msg/detail/light__traits.hpp" + +#endif // ROS_IGN_INTERFACES__LIGHT_HPP_ diff --git a/ros_ign_bridge/src/convert.cpp b/ros_ign_bridge/src/convert.cpp index 3f095f6b..c090e91f 100644 --- a/ros_ign_bridge/src/convert.cpp +++ b/ros_ign_bridge/src/convert.cpp @@ -50,6 +50,102 @@ std::string frame_id_ign_to_ros(const std::string & frame_id) return replace_delimiter(frame_id, "::", "/"); } +template<> +void +convert_ros_to_ign( + const ros_ign_interfaces::msg::Color & ros_msg, + ignition::msgs::Color & ign_msg) +{ + ign_msg.set_r(ros_msg.r); + ign_msg.set_g(ros_msg.g); + ign_msg.set_b(ros_msg.b); + ign_msg.set_a(ros_msg.a); +} + +template<> +void +convert_ign_to_ros( + const ignition::msgs::Color & ign_msg, + ros_ign_interfaces::msg::Color & ros_msg) +{ + ros_msg.r = ign_msg.r(); + ros_msg.g = ign_msg.g(); + ros_msg.b = ign_msg.b(); + ros_msg.a = ign_msg.a(); +} + +template<> +void +convert_ros_to_ign( + const ros_ign_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & ign_msg) +{ + ign_msg.set_name(ros_msg.name); + if (ros_msg.type == 0) { + ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_POINT); + } else if (ros_msg.type == 1) { + ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT); + } else if (ros_msg.type == 2) { + ign_msg.set_type( + ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL); + } + + convert_ros_to_ign(ros_msg.pose, *ign_msg.mutable_pose()); + convert_ros_to_ign(ros_msg.diffuse, *ign_msg.mutable_diffuse()); + convert_ros_to_ign(ros_msg.specular, *ign_msg.mutable_specular()); + ign_msg.set_attenuation_constant(ros_msg.attenuation_constant); + ign_msg.set_attenuation_linear(ros_msg.attenuation_linear); + ign_msg.set_attenuation_quadratic(ros_msg.attenuation_quadratic); + convert_ros_to_ign(ros_msg.direction, *ign_msg.mutable_direction()); + ign_msg.set_range(ros_msg.range); + ign_msg.set_cast_shadows(ros_msg.cast_shadows); + ign_msg.set_spot_inner_angle(ros_msg.spot_inner_angle); + ign_msg.set_spot_outer_angle(ros_msg.spot_outer_angle); + ign_msg.set_spot_falloff(ros_msg.spot_falloff); + + ign_msg.set_id(ros_msg.id); + + ign_msg.set_parent_id(ros_msg.parent_id); + + ign_msg.set_intensity(ros_msg.intensity); +} + +template<> +void +convert_ign_to_ros( + const ignition::msgs::Light & ign_msg, + ros_ign_interfaces::msg::Light & ros_msg) +{ + // ign_msg.set_name(ros_msg.name); + // if (ros_msg.type == 0) { + // ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_POINT); + // } else if (ros_msg.type == 1) { + // ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT); + // } else if (ros_msg.type == 2) { + // ign_msg.set_type( + // ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL); + // } + + // convert_ros_to_ign(ros_msg.pose, *ign_msg.mutable_pose()); + // convert_ros_to_ign(ros_msg.diffuse, *ign_msg.mutable_diffuse()); + // convert_ros_to_ign(ros_msg.specular, *ign_msg.mutable_specular()); + // ign_msg.set_attenuation_constant(ros_msg.attenuation_constant); + // ign_msg.set_attenuation_linear(ros_msg.attenuation_linear); + // ign_msg.set_attenuation_quadratic(ros_msg.attenuation_quadratic); + // convert_ros_to_ign(ros_msg.direction, *ign_msg.mutable_direction()); + // ign_msg.set_range(ros_msg.range); + // ign_msg.set_cast_shadows(ros_msg.cast_shadows); + // ign_msg.set_spot_inner_angle(ros_msg.spot_inner_angle); + // ign_msg.set_spot_outer_angle(ros_msg.spot_outer_angle); + // ign_msg.set_spot_falloff(ros_msg.spot_falloff); + + // ign_msg.set_id(ros_msg.id); + + // ign_msg.set_parent_id(ros_msg.parent_id); + + // ign_msg.set_intensity(ros_msg.intensity); +} + template<> void convert_ros_to_ign( diff --git a/ros_ign_bridge/src/factories.cpp b/ros_ign_bridge/src/factories.cpp index 22163796..fb4839a0 100644 --- a/ros_ign_bridge/src/factories.cpp +++ b/ros_ign_bridge/src/factories.cpp @@ -27,6 +27,26 @@ get_factory_impl( const std::string & ign_type_name) { // mapping from string to specialized template + if ((ros_type_name == "ros_ign_interfaces/msg/Color" || + ros_type_name.empty()) && ign_type_name == "ignition.msgs.Color") + { + return std::make_shared< + Factory< + ros_ign_interfaces::msg::Color, + ignition::msgs::Color + > + >("ros_ign_interfaces/msg/Color", ign_type_name); + } + if ((ros_type_name == "ros_ign_interfaces/msg/Light" || + ros_type_name.empty()) && ign_type_name == "ignition.msgs.Light") + { + return std::make_shared< + Factory< + ros_ign_interfaces::msg::Light, + ignition::msgs::Light + > + >("ros_ign_interfaces/msg/Light", ign_type_name); + } if ((ros_type_name == "std_msgs/msg/Bool" || ros_type_name.empty()) && ign_type_name == "ignition.msgs.Boolean") { @@ -340,6 +360,55 @@ get_factory( // conversion functions for available interfaces +// ros_ign_interfaces +template<> +void +Factory< + ros_ign_interfaces::msg::Color, + ignition::msgs::Color +>::convert_ros_to_ign( + const ros_ign_interfaces::msg::Color & ros_msg, + ignition::msgs::Color & ign_msg) +{ + ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); +} + +template<> +void +Factory< + ros_ign_interfaces::msg::Color, + ignition::msgs::Color +>::convert_ign_to_ros( + const ignition::msgs::Color & ign_msg, + ros_ign_interfaces::msg::Color & ros_msg) +{ + ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); +} + +template<> +void +Factory< + ros_ign_interfaces::msg::Light, + ignition::msgs::Light +>::convert_ros_to_ign( + const ros_ign_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & ign_msg) +{ + ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); +} + +template<> +void +Factory< + ros_ign_interfaces::msg::Light, + ignition::msgs::Light +>::convert_ign_to_ros( + const ignition::msgs::Light & ign_msg, + ros_ign_interfaces::msg::Light & ros_msg) +{ + ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); +} + // std_msgs template<> void diff --git a/ros_ign_bridge/src/factories.hpp b/ros_ign_bridge/src/factories.hpp index bc7943fe..79105943 100644 --- a/ros_ign_bridge/src/factories.hpp +++ b/ros_ign_bridge/src/factories.hpp @@ -46,6 +46,9 @@ // Ignition messages #include +#include +#include + #include #include @@ -60,6 +63,43 @@ get_factory( // conversion functions for available interfaces +// ros_ign_interfaces +template<> +void +Factory< + ros_ign_interfaces::msg::Color, + ignition::msgs::Color +>::convert_ros_to_ign( + const ros_ign_interfaces::msg::Color & ros_msg, + ignition::msgs::Color & ign_msg); + +template<> +void +Factory< + ros_ign_interfaces::msg::Color, + ignition::msgs::Color +>::convert_ign_to_ros( + const ignition::msgs::Color & ign_msg, + ros_ign_interfaces::msg::Color & ros_msg); + +template<> +void +Factory< + ros_ign_interfaces::msg::Light, + ignition::msgs::Light +>::convert_ros_to_ign( + const ros_ign_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & ign_msg); + +template<> +void +Factory< + ros_ign_interfaces::msg::Light, + ignition::msgs::Light +>::convert_ign_to_ros( + const ignition::msgs::Light & ign_msg, + ros_ign_interfaces::msg::Light & ros_msg); + // std_msgs template<> void diff --git a/ros_ign_interfaces/CMakeLists.txt b/ros_ign_interfaces/CMakeLists.txt index b7e1255e..4e6a2c19 100644 --- a/ros_ign_interfaces/CMakeLists.txt +++ b/ros_ign_interfaces/CMakeLists.txt @@ -16,10 +16,12 @@ find_package(geometry_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) set(msg_files + "msg/Color.msg" "msg/Contact.msg" "msg/Contacts.msg" "msg/Entity.msg" "msg/EntityFactory.msg" + "msg/Light.msg" "msg/WorldControl.msg" "msg/WorldReset.msg" ) diff --git a/ros_ign_interfaces/msg/Color.msg b/ros_ign_interfaces/msg/Color.msg new file mode 100644 index 00000000..02096f3d --- /dev/null +++ b/ros_ign_interfaces/msg/Color.msg @@ -0,0 +1,4 @@ +float32 r # Red component +float32 g # Green component +float32 b # Blue component +float32 a # Alpha component diff --git a/ros_ign_interfaces/msg/Light.msg b/ros_ign_interfaces/msg/Light.msg new file mode 100644 index 00000000..e2e1dcc2 --- /dev/null +++ b/ros_ign_interfaces/msg/Light.msg @@ -0,0 +1,27 @@ +string name + +# Light type: constant definition +uint8 POINT = 0 +uint8 SPOT = 1 +uint8 DIRECTIONAL = 2 + +uint8 type + +geometry_msgs/Pose pose +ros_ign_interfaces/Color diffuse +ros_ign_interfaces/Color specular +float32 attenuation_constant +float32 attenuation_linear +float32 attenuation_quadratic +geometry_msgs/Vector3 direction +float32 range +bool cast_shadows +float32 spot_inner_angle +float32 spot_outer_angle +float32 spot_falloff + +uint32 id + +uint32 parent_id + +float32 intensity From 53ab0c84f73fb3ed44ac372c337df78f58d9f5e2 Mon Sep 17 00:00:00 2001 From: William Lew Date: Tue, 9 Nov 2021 13:00:15 -0800 Subject: [PATCH 02/15] Removed rosidl generated headers Signed-off-by: William Lew --- ros_ign_bridge/CMakeLists.txt | 4 + .../include/ros_ign_interfaces/msg/color.hpp | 11 - .../msg/detail/color__builder.hpp | 103 ----- .../msg/detail/color__struct.hpp | 172 -------- .../msg/detail/color__traits.hpp | 96 ----- .../msg/detail/light__builder.hpp | 311 --------------- .../msg/detail/light__struct.hpp | 375 ------------------ .../msg/detail/light__traits.hpp | 231 ----------- .../include/ros_ign_interfaces/msg/light.hpp | 11 - ros_ign_bridge/src/convert.cpp | 58 +-- 10 files changed, 34 insertions(+), 1338 deletions(-) delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp delete mode 100644 ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp diff --git a/ros_ign_bridge/CMakeLists.txt b/ros_ign_bridge/CMakeLists.txt index 6a054cfe..019e87f2 100644 --- a/ros_ign_bridge/CMakeLists.txt +++ b/ros_ign_bridge/CMakeLists.txt @@ -105,6 +105,10 @@ foreach(bridge ${bridge_executables}) target_link_libraries(${bridge} ignition-msgs${IGN_MSGS_VER}::core ignition-transport${IGN_TRANSPORT_VER}::core + # ros_ign_interfaces libraries + -lros_ign_interfaces__rosidl_typesupport_cpp + -lros_ign_interfaces__rosidl_typesupport_fastrtps_cpp + -lros_ign_interfaces__rosidl_typesupport_introspection_cpp ) ament_target_dependencies(${bridge} "geometry_msgs" diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp deleted file mode 100644 index fd893af1..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/color.hpp +++ /dev/null @@ -1,11 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl.hpp.em -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__COLOR_HPP_ -#define ROS_IGN_INTERFACES__COLOR_HPP_ - -#include "ros_ign_interfaces/msg/detail/color__struct.hpp" -#include "ros_ign_interfaces/msg/detail/color__builder.hpp" -#include "ros_ign_interfaces/msg/detail/color__traits.hpp" - -#endif // ROS_IGN_INTERFACES__COLOR_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp deleted file mode 100644 index 6dbdab3b..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__builder.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl__builder.hpp.em -// with input from ros_ign_interfaces:Color.idl -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__DETAIL__COLOR__BUILDER_HPP_ -#define ROS_IGN_INTERFACES__DETAIL__COLOR__BUILDER_HPP_ - -#include "ros_ign_interfaces/msg/detail/color__struct.hpp" -#include -#include -#include - - -namespace ros_ign_interfaces -{ - -namespace msg -{ - -namespace builder -{ - -class Init_Color_a -{ -public: - explicit Init_Color_a(::ros_ign_interfaces::msg::Color & msg) - : msg_(msg) - {} - ::ros_ign_interfaces::msg::Color a(::ros_ign_interfaces::msg::Color::_a_type arg) - { - msg_.a = std::move(arg); - return std::move(msg_); - } - -private: - ::ros_ign_interfaces::msg::Color msg_; -}; - -class Init_Color_b -{ -public: - explicit Init_Color_b(::ros_ign_interfaces::msg::Color & msg) - : msg_(msg) - {} - Init_Color_a b(::ros_ign_interfaces::msg::Color::_b_type arg) - { - msg_.b = std::move(arg); - return Init_Color_a(msg_); - } - -private: - ::ros_ign_interfaces::msg::Color msg_; -}; - -class Init_Color_g -{ -public: - explicit Init_Color_g(::ros_ign_interfaces::msg::Color & msg) - : msg_(msg) - {} - Init_Color_b g(::ros_ign_interfaces::msg::Color::_g_type arg) - { - msg_.g = std::move(arg); - return Init_Color_b(msg_); - } - -private: - ::ros_ign_interfaces::msg::Color msg_; -}; - -class Init_Color_r -{ -public: - Init_Color_r() - : msg_(::rosidl_runtime_cpp::MessageInitialization::SKIP) - {} - Init_Color_g r(::ros_ign_interfaces::msg::Color::_r_type arg) - { - msg_.r = std::move(arg); - return Init_Color_g(msg_); - } - -private: - ::ros_ign_interfaces::msg::Color msg_; -}; - -} // namespace builder - -} // namespace msg - -template -auto build(); - -template<> -inline -auto build<::ros_ign_interfaces::msg::Color>() -{ - return ros_ign_interfaces::msg::builder::Init_Color_r(); -} - -} // namespace ros_ign_interfaces - -#endif // ROS_IGN_INTERFACES__DETAIL__COLOR__BUILDER_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp deleted file mode 100644 index 545a5af4..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__struct.hpp +++ /dev/null @@ -1,172 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl__struct.hpp.em -// with input from ros_ign_interfaces:Color.idl -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__DETAIL__COLOR__STRUCT_HPP_ -#define ROS_IGN_INTERFACES__DETAIL__COLOR__STRUCT_HPP_ - -#include -#include -#include -#include -#include -#include -#include - - -#ifndef _WIN32 -# define DEPRECATED__ros_ign_interfaces__Color __attribute__((deprecated)) -#else -# define DEPRECATED__ros_ign_interfaces__Color __declspec(deprecated) -#endif - -namespace ros_ign_interfaces -{ - -namespace msg -{ - -// message struct -template -struct Color_ -{ - using Type = Color_; - - explicit Color_(rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) - { - if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || - rosidl_runtime_cpp::MessageInitialization::ZERO == _init) - { - this->r = 0.0f; - this->g = 0.0f; - this->b = 0.0f; - this->a = 0.0f; - } - } - - explicit Color_(const ContainerAllocator & _alloc, rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) - { - (void)_alloc; - if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || - rosidl_runtime_cpp::MessageInitialization::ZERO == _init) - { - this->r = 0.0f; - this->g = 0.0f; - this->b = 0.0f; - this->a = 0.0f; - } - } - - // field types and members - using _r_type = - float; - _r_type r; - using _g_type = - float; - _g_type g; - using _b_type = - float; - _b_type b; - using _a_type = - float; - _a_type a; - - // setters for named parameter idiom - Type & set__r( - const float & _arg) - { - this->r = _arg; - return *this; - } - Type & set__g( - const float & _arg) - { - this->g = _arg; - return *this; - } - Type & set__b( - const float & _arg) - { - this->b = _arg; - return *this; - } - Type & set__a( - const float & _arg) - { - this->a = _arg; - return *this; - } - - // constant declarations - - // pointer types - using RawPtr = - ros_ign_interfaces::msg::Color_ *; - using ConstRawPtr = - const ros_ign_interfaces::msg::Color_ *; - using SharedPtr = - std::shared_ptr>; - using ConstSharedPtr = - std::shared_ptr const>; - - template>> - using UniquePtrWithDeleter = - std::unique_ptr, Deleter>; - - using UniquePtr = UniquePtrWithDeleter<>; - - template>> - using ConstUniquePtrWithDeleter = - std::unique_ptr const, Deleter>; - using ConstUniquePtr = ConstUniquePtrWithDeleter<>; - - using WeakPtr = - std::weak_ptr>; - using ConstWeakPtr = - std::weak_ptr const>; - - // pointer types similar to ROS 1, use SharedPtr / ConstSharedPtr instead - // NOTE: Can't use 'using' here because GNU C++ can't parse attributes properly - typedef DEPRECATED__ros_ign_interfaces__Color - std::shared_ptr> - Ptr; - typedef DEPRECATED__ros_ign_interfaces__Color - std::shared_ptr const> - ConstPtr; - - // comparison operators - bool operator==(const Color_ & other) const - { - if (this->r != other.r) { - return false; - } - if (this->g != other.g) { - return false; - } - if (this->b != other.b) { - return false; - } - if (this->a != other.a) { - return false; - } - return true; - } - bool operator!=(const Color_ & other) const - { - return !this->operator==(other); - } -}; // struct Color_ - -// alias to use template instance with default allocator -using Color = - ros_ign_interfaces::msg::Color_>; - -// constant definitions - -} // namespace msg - -} // namespace ros_ign_interfaces - -#endif // ROS_IGN_INTERFACES__DETAIL__COLOR__STRUCT_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp deleted file mode 100644 index 04ea5b2b..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/color__traits.hpp +++ /dev/null @@ -1,96 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl__traits.hpp.em -// with input from ros_ign_interfaces:Color.idl -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__DETAIL__COLOR__TRAITS_HPP_ -#define ROS_IGN_INTERFACES__DETAIL__COLOR__TRAITS_HPP_ - -#include "ros_ign_interfaces/msg/detail/color__struct.hpp" -#include -#include -#include -#include -#include - -namespace rosidl_generator_traits -{ - -inline void to_yaml( - const ros_ign_interfaces::msg::Color & msg, - std::ostream & out, size_t indentation = 0) -{ - // member: r - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "r: "; - value_to_yaml(msg.r, out); - out << "\n"; - } - - // member: g - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "g: "; - value_to_yaml(msg.g, out); - out << "\n"; - } - - // member: b - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "b: "; - value_to_yaml(msg.b, out); - out << "\n"; - } - - // member: a - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "a: "; - value_to_yaml(msg.a, out); - out << "\n"; - } -} // NOLINT(readability/fn_size) - -inline std::string to_yaml(const ros_ign_interfaces::msg::Color & msg) -{ - std::ostringstream out; - to_yaml(msg, out); - return out.str(); -} - -template<> -inline const char * data_type() -{ - return "ros_ign_interfaces::msg::Color"; -} - -template<> -inline const char * name() -{ - return "ros_ign_interfaces/msg/Color"; -} - -template<> -struct has_fixed_size - : std::integral_constant {}; - -template<> -struct has_bounded_size - : std::integral_constant {}; - -template<> -struct is_message - : std::true_type {}; - -} // namespace rosidl_generator_traits - -#endif // ROS_IGN_INTERFACES__DETAIL__COLOR__TRAITS_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp deleted file mode 100644 index 005763cb..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__builder.hpp +++ /dev/null @@ -1,311 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl__builder.hpp.em -// with input from ros_ign_interfaces:Light.idl -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__DETAIL__LIGHT__BUILDER_HPP_ -#define ROS_IGN_INTERFACES__DETAIL__LIGHT__BUILDER_HPP_ - -#include "ros_ign_interfaces/msg/detail/light__struct.hpp" -#include -#include -#include - - -namespace ros_ign_interfaces -{ - -namespace msg -{ - -namespace builder -{ - -class Init_Light_intensity -{ -public: - explicit Init_Light_intensity(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - ::ros_ign_interfaces::msg::Light intensity(::ros_ign_interfaces::msg::Light::_intensity_type arg) - { - msg_.intensity = std::move(arg); - return std::move(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_parent_id -{ -public: - explicit Init_Light_parent_id(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_intensity parent_id(::ros_ign_interfaces::msg::Light::_parent_id_type arg) - { - msg_.parent_id = std::move(arg); - return Init_Light_intensity(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_id -{ -public: - explicit Init_Light_id(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_parent_id id(::ros_ign_interfaces::msg::Light::_id_type arg) - { - msg_.id = std::move(arg); - return Init_Light_parent_id(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_spot_falloff -{ -public: - explicit Init_Light_spot_falloff(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_id spot_falloff(::ros_ign_interfaces::msg::Light::_spot_falloff_type arg) - { - msg_.spot_falloff = std::move(arg); - return Init_Light_id(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_spot_outer_angle -{ -public: - explicit Init_Light_spot_outer_angle(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_spot_falloff spot_outer_angle(::ros_ign_interfaces::msg::Light::_spot_outer_angle_type arg) - { - msg_.spot_outer_angle = std::move(arg); - return Init_Light_spot_falloff(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_spot_inner_angle -{ -public: - explicit Init_Light_spot_inner_angle(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_spot_outer_angle spot_inner_angle(::ros_ign_interfaces::msg::Light::_spot_inner_angle_type arg) - { - msg_.spot_inner_angle = std::move(arg); - return Init_Light_spot_outer_angle(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_cast_shadows -{ -public: - explicit Init_Light_cast_shadows(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_spot_inner_angle cast_shadows(::ros_ign_interfaces::msg::Light::_cast_shadows_type arg) - { - msg_.cast_shadows = std::move(arg); - return Init_Light_spot_inner_angle(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_range -{ -public: - explicit Init_Light_range(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_cast_shadows range(::ros_ign_interfaces::msg::Light::_range_type arg) - { - msg_.range = std::move(arg); - return Init_Light_cast_shadows(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_direction -{ -public: - explicit Init_Light_direction(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_range direction(::ros_ign_interfaces::msg::Light::_direction_type arg) - { - msg_.direction = std::move(arg); - return Init_Light_range(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_attenuation_quadratic -{ -public: - explicit Init_Light_attenuation_quadratic(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_direction attenuation_quadratic(::ros_ign_interfaces::msg::Light::_attenuation_quadratic_type arg) - { - msg_.attenuation_quadratic = std::move(arg); - return Init_Light_direction(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_attenuation_linear -{ -public: - explicit Init_Light_attenuation_linear(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_attenuation_quadratic attenuation_linear(::ros_ign_interfaces::msg::Light::_attenuation_linear_type arg) - { - msg_.attenuation_linear = std::move(arg); - return Init_Light_attenuation_quadratic(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_attenuation_constant -{ -public: - explicit Init_Light_attenuation_constant(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_attenuation_linear attenuation_constant(::ros_ign_interfaces::msg::Light::_attenuation_constant_type arg) - { - msg_.attenuation_constant = std::move(arg); - return Init_Light_attenuation_linear(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_specular -{ -public: - explicit Init_Light_specular(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_attenuation_constant specular(::ros_ign_interfaces::msg::Light::_specular_type arg) - { - msg_.specular = std::move(arg); - return Init_Light_attenuation_constant(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_diffuse -{ -public: - explicit Init_Light_diffuse(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_specular diffuse(::ros_ign_interfaces::msg::Light::_diffuse_type arg) - { - msg_.diffuse = std::move(arg); - return Init_Light_specular(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_pose -{ -public: - explicit Init_Light_pose(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_diffuse pose(::ros_ign_interfaces::msg::Light::_pose_type arg) - { - msg_.pose = std::move(arg); - return Init_Light_diffuse(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_type -{ -public: - explicit Init_Light_type(::ros_ign_interfaces::msg::Light & msg) - : msg_(msg) - {} - Init_Light_pose type(::ros_ign_interfaces::msg::Light::_type_type arg) - { - msg_.type = std::move(arg); - return Init_Light_pose(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -class Init_Light_name -{ -public: - Init_Light_name() - : msg_(::rosidl_runtime_cpp::MessageInitialization::SKIP) - {} - Init_Light_type name(::ros_ign_interfaces::msg::Light::_name_type arg) - { - msg_.name = std::move(arg); - return Init_Light_type(msg_); - } - -private: - ::ros_ign_interfaces::msg::Light msg_; -}; - -} // namespace builder - -} // namespace msg - -template -auto build(); - -template<> -inline -auto build<::ros_ign_interfaces::msg::Light>() -{ - return ros_ign_interfaces::msg::builder::Init_Light_name(); -} - -} // namespace ros_ign_interfaces - -#endif // ROS_IGN_INTERFACES__DETAIL__LIGHT__BUILDER_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp deleted file mode 100644 index 8f4561ca..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__struct.hpp +++ /dev/null @@ -1,375 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl__struct.hpp.em -// with input from ros_ign_interfaces:Light.idl -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__DETAIL__LIGHT__STRUCT_HPP_ -#define ROS_IGN_INTERFACES__DETAIL__LIGHT__STRUCT_HPP_ - -#include -#include -#include -#include -#include -#include -#include - - -// Include directives for member types -// Member 'pose' -#include "geometry_msgs/msg/detail/pose__struct.hpp" -// Member 'diffuse' -// Member 'specular' -#include "ros_ign_interfaces/msg/detail/color__struct.hpp" -// Member 'direction' -#include "geometry_msgs/msg/detail/vector3__struct.hpp" - -#ifndef _WIN32 -# define DEPRECATED__ros_ign_interfaces__Light __attribute__((deprecated)) -#else -# define DEPRECATED__ros_ign_interfaces__Light __declspec(deprecated) -#endif - -namespace ros_ign_interfaces -{ - -namespace msg -{ - -// message struct -template -struct Light_ -{ - using Type = Light_; - - explicit Light_(rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) - : pose(_init), - diffuse(_init), - specular(_init), - direction(_init) - { - if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || - rosidl_runtime_cpp::MessageInitialization::ZERO == _init) - { - this->name = ""; - this->type = 0; - this->attenuation_constant = 0.0f; - this->attenuation_linear = 0.0f; - this->attenuation_quadratic = 0.0f; - this->range = 0.0f; - this->cast_shadows = false; - this->spot_inner_angle = 0.0f; - this->spot_outer_angle = 0.0f; - this->spot_falloff = 0.0f; - this->id = 0ul; - this->parent_id = 0ul; - this->intensity = 0.0f; - } - } - - explicit Light_(const ContainerAllocator & _alloc, rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL) - : name(_alloc), - pose(_alloc, _init), - diffuse(_alloc, _init), - specular(_alloc, _init), - direction(_alloc, _init) - { - if (rosidl_runtime_cpp::MessageInitialization::ALL == _init || - rosidl_runtime_cpp::MessageInitialization::ZERO == _init) - { - this->name = ""; - this->type = 0; - this->attenuation_constant = 0.0f; - this->attenuation_linear = 0.0f; - this->attenuation_quadratic = 0.0f; - this->range = 0.0f; - this->cast_shadows = false; - this->spot_inner_angle = 0.0f; - this->spot_outer_angle = 0.0f; - this->spot_falloff = 0.0f; - this->id = 0ul; - this->parent_id = 0ul; - this->intensity = 0.0f; - } - } - - // field types and members - using _name_type = - std::basic_string, typename std::allocator_traits::template rebind_alloc>; - _name_type name; - using _type_type = - uint8_t; - _type_type type; - using _pose_type = - geometry_msgs::msg::Pose_; - _pose_type pose; - using _diffuse_type = - ros_ign_interfaces::msg::Color_; - _diffuse_type diffuse; - using _specular_type = - ros_ign_interfaces::msg::Color_; - _specular_type specular; - using _attenuation_constant_type = - float; - _attenuation_constant_type attenuation_constant; - using _attenuation_linear_type = - float; - _attenuation_linear_type attenuation_linear; - using _attenuation_quadratic_type = - float; - _attenuation_quadratic_type attenuation_quadratic; - using _direction_type = - geometry_msgs::msg::Vector3_; - _direction_type direction; - using _range_type = - float; - _range_type range; - using _cast_shadows_type = - bool; - _cast_shadows_type cast_shadows; - using _spot_inner_angle_type = - float; - _spot_inner_angle_type spot_inner_angle; - using _spot_outer_angle_type = - float; - _spot_outer_angle_type spot_outer_angle; - using _spot_falloff_type = - float; - _spot_falloff_type spot_falloff; - using _id_type = - uint32_t; - _id_type id; - using _parent_id_type = - uint32_t; - _parent_id_type parent_id; - using _intensity_type = - float; - _intensity_type intensity; - - // setters for named parameter idiom - Type & set__name( - const std::basic_string, typename std::allocator_traits::template rebind_alloc> & _arg) - { - this->name = _arg; - return *this; - } - Type & set__type( - const uint8_t & _arg) - { - this->type = _arg; - return *this; - } - Type & set__pose( - const geometry_msgs::msg::Pose_ & _arg) - { - this->pose = _arg; - return *this; - } - Type & set__diffuse( - const ros_ign_interfaces::msg::Color_ & _arg) - { - this->diffuse = _arg; - return *this; - } - Type & set__specular( - const ros_ign_interfaces::msg::Color_ & _arg) - { - this->specular = _arg; - return *this; - } - Type & set__attenuation_constant( - const float & _arg) - { - this->attenuation_constant = _arg; - return *this; - } - Type & set__attenuation_linear( - const float & _arg) - { - this->attenuation_linear = _arg; - return *this; - } - Type & set__attenuation_quadratic( - const float & _arg) - { - this->attenuation_quadratic = _arg; - return *this; - } - Type & set__direction( - const geometry_msgs::msg::Vector3_ & _arg) - { - this->direction = _arg; - return *this; - } - Type & set__range( - const float & _arg) - { - this->range = _arg; - return *this; - } - Type & set__cast_shadows( - const bool & _arg) - { - this->cast_shadows = _arg; - return *this; - } - Type & set__spot_inner_angle( - const float & _arg) - { - this->spot_inner_angle = _arg; - return *this; - } - Type & set__spot_outer_angle( - const float & _arg) - { - this->spot_outer_angle = _arg; - return *this; - } - Type & set__spot_falloff( - const float & _arg) - { - this->spot_falloff = _arg; - return *this; - } - Type & set__id( - const uint32_t & _arg) - { - this->id = _arg; - return *this; - } - Type & set__parent_id( - const uint32_t & _arg) - { - this->parent_id = _arg; - return *this; - } - Type & set__intensity( - const float & _arg) - { - this->intensity = _arg; - return *this; - } - - // constant declarations - static constexpr uint8_t POINT = - 0u; - static constexpr uint8_t SPOT = - 1u; - static constexpr uint8_t DIRECTIONAL = - 2u; - - // pointer types - using RawPtr = - ros_ign_interfaces::msg::Light_ *; - using ConstRawPtr = - const ros_ign_interfaces::msg::Light_ *; - using SharedPtr = - std::shared_ptr>; - using ConstSharedPtr = - std::shared_ptr const>; - - template>> - using UniquePtrWithDeleter = - std::unique_ptr, Deleter>; - - using UniquePtr = UniquePtrWithDeleter<>; - - template>> - using ConstUniquePtrWithDeleter = - std::unique_ptr const, Deleter>; - using ConstUniquePtr = ConstUniquePtrWithDeleter<>; - - using WeakPtr = - std::weak_ptr>; - using ConstWeakPtr = - std::weak_ptr const>; - - // pointer types similar to ROS 1, use SharedPtr / ConstSharedPtr instead - // NOTE: Can't use 'using' here because GNU C++ can't parse attributes properly - typedef DEPRECATED__ros_ign_interfaces__Light - std::shared_ptr> - Ptr; - typedef DEPRECATED__ros_ign_interfaces__Light - std::shared_ptr const> - ConstPtr; - - // comparison operators - bool operator==(const Light_ & other) const - { - if (this->name != other.name) { - return false; - } - if (this->type != other.type) { - return false; - } - if (this->pose != other.pose) { - return false; - } - if (this->diffuse != other.diffuse) { - return false; - } - if (this->specular != other.specular) { - return false; - } - if (this->attenuation_constant != other.attenuation_constant) { - return false; - } - if (this->attenuation_linear != other.attenuation_linear) { - return false; - } - if (this->attenuation_quadratic != other.attenuation_quadratic) { - return false; - } - if (this->direction != other.direction) { - return false; - } - if (this->range != other.range) { - return false; - } - if (this->cast_shadows != other.cast_shadows) { - return false; - } - if (this->spot_inner_angle != other.spot_inner_angle) { - return false; - } - if (this->spot_outer_angle != other.spot_outer_angle) { - return false; - } - if (this->spot_falloff != other.spot_falloff) { - return false; - } - if (this->id != other.id) { - return false; - } - if (this->parent_id != other.parent_id) { - return false; - } - if (this->intensity != other.intensity) { - return false; - } - return true; - } - bool operator!=(const Light_ & other) const - { - return !this->operator==(other); - } -}; // struct Light_ - -// alias to use template instance with default allocator -using Light = - ros_ign_interfaces::msg::Light_>; - -// constant definitions -template -constexpr uint8_t Light_::POINT; -template -constexpr uint8_t Light_::SPOT; -template -constexpr uint8_t Light_::DIRECTIONAL; - -} // namespace msg - -} // namespace ros_ign_interfaces - -#endif // ROS_IGN_INTERFACES__DETAIL__LIGHT__STRUCT_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp deleted file mode 100644 index 7ef94e76..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/detail/light__traits.hpp +++ /dev/null @@ -1,231 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl__traits.hpp.em -// with input from ros_ign_interfaces:Light.idl -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__DETAIL__LIGHT__TRAITS_HPP_ -#define ROS_IGN_INTERFACES__DETAIL__LIGHT__TRAITS_HPP_ - -#include "ros_ign_interfaces/msg/detail/light__struct.hpp" -#include -#include -#include -#include -#include - -// Include directives for member types -// Member 'pose' -#include "geometry_msgs/msg/detail/pose__traits.hpp" -// Member 'diffuse' -// Member 'specular' -#include "ros_ign_interfaces/msg/detail/color__traits.hpp" -// Member 'direction' -#include "geometry_msgs/msg/detail/vector3__traits.hpp" - -namespace rosidl_generator_traits -{ - -inline void to_yaml( - const ros_ign_interfaces::msg::Light & msg, - std::ostream & out, size_t indentation = 0) -{ - // member: name - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "name: "; - value_to_yaml(msg.name, out); - out << "\n"; - } - - // member: type - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "type: "; - value_to_yaml(msg.type, out); - out << "\n"; - } - - // member: pose - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "pose:\n"; - to_yaml(msg.pose, out, indentation + 2); - } - - // member: diffuse - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "diffuse:\n"; - to_yaml(msg.diffuse, out, indentation + 2); - } - - // member: specular - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "specular:\n"; - to_yaml(msg.specular, out, indentation + 2); - } - - // member: attenuation_constant - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "attenuation_constant: "; - value_to_yaml(msg.attenuation_constant, out); - out << "\n"; - } - - // member: attenuation_linear - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "attenuation_linear: "; - value_to_yaml(msg.attenuation_linear, out); - out << "\n"; - } - - // member: attenuation_quadratic - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "attenuation_quadratic: "; - value_to_yaml(msg.attenuation_quadratic, out); - out << "\n"; - } - - // member: direction - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "direction:\n"; - to_yaml(msg.direction, out, indentation + 2); - } - - // member: range - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "range: "; - value_to_yaml(msg.range, out); - out << "\n"; - } - - // member: cast_shadows - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "cast_shadows: "; - value_to_yaml(msg.cast_shadows, out); - out << "\n"; - } - - // member: spot_inner_angle - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "spot_inner_angle: "; - value_to_yaml(msg.spot_inner_angle, out); - out << "\n"; - } - - // member: spot_outer_angle - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "spot_outer_angle: "; - value_to_yaml(msg.spot_outer_angle, out); - out << "\n"; - } - - // member: spot_falloff - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "spot_falloff: "; - value_to_yaml(msg.spot_falloff, out); - out << "\n"; - } - - // member: id - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "id: "; - value_to_yaml(msg.id, out); - out << "\n"; - } - - // member: parent_id - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "parent_id: "; - value_to_yaml(msg.parent_id, out); - out << "\n"; - } - - // member: intensity - { - if (indentation > 0) { - out << std::string(indentation, ' '); - } - out << "intensity: "; - value_to_yaml(msg.intensity, out); - out << "\n"; - } -} // NOLINT(readability/fn_size) - -inline std::string to_yaml(const ros_ign_interfaces::msg::Light & msg) -{ - std::ostringstream out; - to_yaml(msg, out); - return out.str(); -} - -template<> -inline const char * data_type() -{ - return "ros_ign_interfaces::msg::Light"; -} - -template<> -inline const char * name() -{ - return "ros_ign_interfaces/msg/Light"; -} - -template<> -struct has_fixed_size - : std::integral_constant {}; - -template<> -struct has_bounded_size - : std::integral_constant {}; - -template<> -struct is_message - : std::true_type {}; - -} // namespace rosidl_generator_traits - -#endif // ROS_IGN_INTERFACES__DETAIL__LIGHT__TRAITS_HPP_ diff --git a/ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp b/ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp deleted file mode 100644 index cac4d304..00000000 --- a/ros_ign_bridge/include/ros_ign_interfaces/msg/light.hpp +++ /dev/null @@ -1,11 +0,0 @@ -// generated from rosidl_generator_cpp/resource/idl.hpp.em -// generated code does not contain a copyright notice - -#ifndef ROS_IGN_INTERFACES__LIGHT_HPP_ -#define ROS_IGN_INTERFACES__LIGHT_HPP_ - -#include "ros_ign_interfaces/msg/detail/light__struct.hpp" -#include "ros_ign_interfaces/msg/detail/light__builder.hpp" -#include "ros_ign_interfaces/msg/detail/light__traits.hpp" - -#endif // ROS_IGN_INTERFACES__LIGHT_HPP_ diff --git a/ros_ign_bridge/src/convert.cpp b/ros_ign_bridge/src/convert.cpp index c090e91f..01ed6fc0 100644 --- a/ros_ign_bridge/src/convert.cpp +++ b/ros_ign_bridge/src/convert.cpp @@ -116,34 +116,36 @@ convert_ign_to_ros( const ignition::msgs::Light & ign_msg, ros_ign_interfaces::msg::Light & ros_msg) { - // ign_msg.set_name(ros_msg.name); - // if (ros_msg.type == 0) { - // ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_POINT); - // } else if (ros_msg.type == 1) { - // ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT); - // } else if (ros_msg.type == 2) { - // ign_msg.set_type( - // ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL); - // } - - // convert_ros_to_ign(ros_msg.pose, *ign_msg.mutable_pose()); - // convert_ros_to_ign(ros_msg.diffuse, *ign_msg.mutable_diffuse()); - // convert_ros_to_ign(ros_msg.specular, *ign_msg.mutable_specular()); - // ign_msg.set_attenuation_constant(ros_msg.attenuation_constant); - // ign_msg.set_attenuation_linear(ros_msg.attenuation_linear); - // ign_msg.set_attenuation_quadratic(ros_msg.attenuation_quadratic); - // convert_ros_to_ign(ros_msg.direction, *ign_msg.mutable_direction()); - // ign_msg.set_range(ros_msg.range); - // ign_msg.set_cast_shadows(ros_msg.cast_shadows); - // ign_msg.set_spot_inner_angle(ros_msg.spot_inner_angle); - // ign_msg.set_spot_outer_angle(ros_msg.spot_outer_angle); - // ign_msg.set_spot_falloff(ros_msg.spot_falloff); - - // ign_msg.set_id(ros_msg.id); - - // ign_msg.set_parent_id(ros_msg.parent_id); - - // ign_msg.set_intensity(ros_msg.intensity); + ros_msg.name = ign_msg.name(); + if (ign_msg.type() == + ignition::msgs::Light_LightType::Light_LightType_POINT) { + ros_msg.type = 0; + } else if (ign_msg.type() == + ignition::msgs::Light_LightType::Light_LightType_SPOT) { + ros_msg.type = 1; + } else if (ign_msg.type() == + ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL) { + ros_msg.type = 2; + } + + convert_ign_to_ros(ign_msg.pose(), ros_msg.pose); + convert_ign_to_ros(ign_msg.diffuse(), ros_msg.diffuse); + convert_ign_to_ros(ign_msg.specular(), ros_msg.specular); + ros_msg.attenuation_constant = ign_msg.attenuation_constant(); + ros_msg.attenuation_linear = ign_msg.attenuation_linear(); + ros_msg.attenuation_quadratic = ign_msg.attenuation_quadratic(); + convert_ign_to_ros(ign_msg.direction(), ros_msg.direction); + ros_msg.range = ign_msg.range(); + ros_msg.cast_shadows = ign_msg.cast_shadows(); + ros_msg.spot_inner_angle = ign_msg.spot_inner_angle(); + ros_msg.spot_outer_angle = ign_msg.spot_outer_angle(); + ros_msg.spot_falloff = ign_msg.spot_falloff(); + + ros_msg.id = ign_msg.id(); + + ros_msg.parent_id = ign_msg.parent_id(); + + ros_msg.intensity = ign_msg.intensity(); } template<> From 6193d6468f87abbf79b14a1fb20882a996fecb8b Mon Sep 17 00:00:00 2001 From: William Lew Date: Tue, 16 Nov 2021 11:36:40 -0800 Subject: [PATCH 03/15] Added header to Color and Light ROS messages Signed-off-by: William Lew --- ros_ign_bridge/src/convert.cpp | 8 ++++++++ ros_ign_interfaces/msg/Color.msg | 2 ++ ros_ign_interfaces/msg/Light.msg | 2 ++ 3 files changed, 12 insertions(+) diff --git a/ros_ign_bridge/src/convert.cpp b/ros_ign_bridge/src/convert.cpp index 01ed6fc0..8ff6c163 100644 --- a/ros_ign_bridge/src/convert.cpp +++ b/ros_ign_bridge/src/convert.cpp @@ -56,6 +56,8 @@ convert_ros_to_ign( const ros_ign_interfaces::msg::Color & ros_msg, ignition::msgs::Color & ign_msg) { + convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + ign_msg.set_r(ros_msg.r); ign_msg.set_g(ros_msg.g); ign_msg.set_b(ros_msg.b); @@ -68,6 +70,8 @@ convert_ign_to_ros( const ignition::msgs::Color & ign_msg, ros_ign_interfaces::msg::Color & ros_msg) { + convert_ign_to_ros(ign_msg.header(), ros_msg.header); + ros_msg.r = ign_msg.r(); ros_msg.g = ign_msg.g(); ros_msg.b = ign_msg.b(); @@ -80,6 +84,8 @@ convert_ros_to_ign( const ros_ign_interfaces::msg::Light & ros_msg, ignition::msgs::Light & ign_msg) { + convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + ign_msg.set_name(ros_msg.name); if (ros_msg.type == 0) { ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_POINT); @@ -116,6 +122,8 @@ convert_ign_to_ros( const ignition::msgs::Light & ign_msg, ros_ign_interfaces::msg::Light & ros_msg) { + convert_ign_to_ros(ign_msg.header(), ros_msg.header); + ros_msg.name = ign_msg.name(); if (ign_msg.type() == ignition::msgs::Light_LightType::Light_LightType_POINT) { diff --git a/ros_ign_interfaces/msg/Color.msg b/ros_ign_interfaces/msg/Color.msg index 02096f3d..82c8d3d5 100644 --- a/ros_ign_interfaces/msg/Color.msg +++ b/ros_ign_interfaces/msg/Color.msg @@ -1,3 +1,5 @@ +std_msgs/Header header + float32 r # Red component float32 g # Green component float32 b # Blue component diff --git a/ros_ign_interfaces/msg/Light.msg b/ros_ign_interfaces/msg/Light.msg index e2e1dcc2..1aae29d8 100644 --- a/ros_ign_interfaces/msg/Light.msg +++ b/ros_ign_interfaces/msg/Light.msg @@ -1,3 +1,5 @@ +std_msgs/Header header + string name # Light type: constant definition From 182bf81b93b8fc163bcf78b1a44ae5557ac3d4f4 Mon Sep 17 00:00:00 2001 From: William Lew Date: Tue, 30 Nov 2021 11:08:09 -0800 Subject: [PATCH 04/15] Updated CMakeLists Signed-off-by: William Lew --- ros_ign_bridge/CMakeLists.txt | 5 +---- ros_ign_interfaces/CMakeLists.txt | 1 + 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/ros_ign_bridge/CMakeLists.txt b/ros_ign_bridge/CMakeLists.txt index 019e87f2..7a2dc137 100644 --- a/ros_ign_bridge/CMakeLists.txt +++ b/ros_ign_bridge/CMakeLists.txt @@ -105,12 +105,9 @@ foreach(bridge ${bridge_executables}) target_link_libraries(${bridge} ignition-msgs${IGN_MSGS_VER}::core ignition-transport${IGN_TRANSPORT_VER}::core - # ros_ign_interfaces libraries - -lros_ign_interfaces__rosidl_typesupport_cpp - -lros_ign_interfaces__rosidl_typesupport_fastrtps_cpp - -lros_ign_interfaces__rosidl_typesupport_introspection_cpp ) ament_target_dependencies(${bridge} + "ros_ign_interfaces" "geometry_msgs" "nav_msgs" "rclcpp" diff --git a/ros_ign_interfaces/CMakeLists.txt b/ros_ign_interfaces/CMakeLists.txt index 4e6a2c19..c55e825c 100644 --- a/ros_ign_interfaces/CMakeLists.txt +++ b/ros_ign_interfaces/CMakeLists.txt @@ -40,5 +40,6 @@ rosidl_generate_interfaces(${PROJECT_NAME} ADD_LINTER_TESTS ) +ament_export_libraries(${PROJECT_NAME}) ament_export_dependencies(rosidl_default_runtime) ament_package() From 3085ddcef4fe5add15cf45833d3d3799450e6567 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 2 Dec 2021 10:46:08 +0100 Subject: [PATCH 05/15] suggestions to PR #187 Signed-off-by: ahcorde --- ros_ign_bridge/CMakeLists.txt | 6 ++++-- ros_ign_bridge/package.xml | 1 + ros_ign_interfaces/CMakeLists.txt | 3 +-- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/ros_ign_bridge/CMakeLists.txt b/ros_ign_bridge/CMakeLists.txt index 7a2dc137..318d0bc8 100644 --- a/ros_ign_bridge/CMakeLists.txt +++ b/ros_ign_bridge/CMakeLists.txt @@ -15,6 +15,7 @@ find_package(geometry_msgs REQUIRED) find_package(nav_msgs REQUIRED) find_package(rclcpp REQUIRED) find_package(rosgraph_msgs REQUIRED) +find_package(ros_ign_interfaces REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2_msgs REQUIRED) @@ -78,6 +79,7 @@ ament_target_dependencies(${bridge_lib} "nav_msgs" "rclcpp" "rosgraph_msgs" + "ros_ign_interfaces" "sensor_msgs" "std_msgs" "tf2_msgs" @@ -100,18 +102,18 @@ ament_export_libraries(${bridge_lib}) foreach(bridge ${bridge_executables}) add_executable(${bridge} src/${bridge}.cpp - ${common_sources} ) target_link_libraries(${bridge} ignition-msgs${IGN_MSGS_VER}::core ignition-transport${IGN_TRANSPORT_VER}::core + ${bridge_lib} ) ament_target_dependencies(${bridge} - "ros_ign_interfaces" "geometry_msgs" "nav_msgs" "rclcpp" "rosgraph_msgs" + "ros_ign_interfaces" "sensor_msgs" "std_msgs" "tf2_msgs" diff --git a/ros_ign_bridge/package.xml b/ros_ign_bridge/package.xml index a8817e94..062d3c19 100644 --- a/ros_ign_bridge/package.xml +++ b/ros_ign_bridge/package.xml @@ -17,6 +17,7 @@ nav_msgs rclcpp rosgraph_msgs + ros_ign_interfaces sensor_msgs std_msgs tf2_msgs diff --git a/ros_ign_interfaces/CMakeLists.txt b/ros_ign_interfaces/CMakeLists.txt index c55e825c..fd283700 100644 --- a/ros_ign_interfaces/CMakeLists.txt +++ b/ros_ign_interfaces/CMakeLists.txt @@ -36,10 +36,9 @@ set(srv_files rosidl_generate_interfaces(${PROJECT_NAME} ${msg_files} ${srv_files} - DEPENDENCIES builtin_interfaces std_msgs geometry_msgs + DEPENDENCIES builtin_interfaces std_msgs geometry_msgs ADD_LINTER_TESTS ) -ament_export_libraries(${PROJECT_NAME}) ament_export_dependencies(rosidl_default_runtime) ament_package() From 0ce66fb2751341c7f6ffb5e141d39f89c46a1904 Mon Sep 17 00:00:00 2001 From: William Lew Date: Thu, 2 Dec 2021 11:27:28 -0800 Subject: [PATCH 06/15] Added ros_ign_interfaces dependency for ros_ign_image Signed-off-by: William Lew --- ros_ign_image/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ros_ign_image/CMakeLists.txt b/ros_ign_image/CMakeLists.txt index 53b503cc..d7a0e434 100644 --- a/ros_ign_image/CMakeLists.txt +++ b/ros_ign_image/CMakeLists.txt @@ -13,6 +13,7 @@ endif() find_package(ament_cmake REQUIRED) find_package(image_transport REQUIRED) find_package(ros_ign_bridge REQUIRED) +find_package(ros_ign_interfaces REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) @@ -64,6 +65,7 @@ target_link_libraries(${executable} ament_target_dependencies(${executable} "image_transport" "ros_ign_bridge" + "ros_ign_interfaces" "rclcpp" "sensor_msgs" ) From de91bbb542934131b2cd4bec920f1abaa4154218 Mon Sep 17 00:00:00 2001 From: William Lew Date: Thu, 9 Dec 2021 16:08:21 -0800 Subject: [PATCH 07/15] Applied code suggestions Signed-off-by: William Lew --- ros_ign_bridge/CMakeLists.txt | 3 -- .../include/ros_ign_bridge/convert.hpp | 19 ++++--- ros_ign_bridge/package.xml | 1 - ros_ign_bridge/src/convert.cpp | 52 +++++++++--------- ros_ign_bridge/src/factories.cpp | 54 +++++++++---------- ros_ign_bridge/src/factories.hpp | 35 ++++++------ ros_ign_interfaces/CMakeLists.txt | 1 - ros_ign_interfaces/msg/Color.msg | 6 --- ros_ign_interfaces/msg/Light.msg | 4 +- 9 files changed, 79 insertions(+), 96 deletions(-) delete mode 100644 ros_ign_interfaces/msg/Color.msg diff --git a/ros_ign_bridge/CMakeLists.txt b/ros_ign_bridge/CMakeLists.txt index 59ee2b6f..40cd82d1 100644 --- a/ros_ign_bridge/CMakeLists.txt +++ b/ros_ign_bridge/CMakeLists.txt @@ -16,7 +16,6 @@ find_package(nav_msgs REQUIRED) find_package(rclcpp REQUIRED) find_package(ros_ign_interfaces REQUIRED) find_package(rosgraph_msgs REQUIRED) -find_package(ros_ign_interfaces REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2_msgs REQUIRED) @@ -90,7 +89,6 @@ ament_target_dependencies(${bridge_lib} "rclcpp" "ros_ign_interfaces" "rosgraph_msgs" - "ros_ign_interfaces" "sensor_msgs" "std_msgs" "tf2_msgs" @@ -125,7 +123,6 @@ foreach(bridge ${bridge_executables}) "rclcpp" "ros_ign_interfaces" "rosgraph_msgs" - "ros_ign_interfaces" "sensor_msgs" "std_msgs" "tf2_msgs" diff --git a/ros_ign_bridge/include/ros_ign_bridge/convert.hpp b/ros_ign_bridge/include/ros_ign_bridge/convert.hpp index 4c8f2c8f..88e48ae6 100644 --- a/ros_ign_bridge/include/ros_ign_bridge/convert.hpp +++ b/ros_ign_bridge/include/ros_ign_bridge/convert.hpp @@ -56,7 +56,6 @@ #include -#include #include namespace ros_ign_bridge @@ -66,28 +65,28 @@ namespace ros_ign_bridge template<> void convert_ros_to_ign( - const ros_ign_interfaces::msg::Color & ros_msg, - ignition::msgs::Color & ign_msg); + const ros_ign_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & ign_msg); template<> void convert_ign_to_ros( - const ignition::msgs::Color & ign_msg, - ros_ign_interfaces::msg::Color & ros_msg); + const ignition::msgs::Light & ign_msg, + ros_ign_interfaces::msg::Light & ros_msg); +// std_msgs template<> void convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg); + const std_msgs::msg::ColorRGBA & ros_msg, + ignition::msgs::Color & ign_msg); template<> void convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg); + const ignition::msgs::Color & ign_msg, + std_msgs::msg::ColorRGBA & ros_msg); -// std_msgs template<> void convert_ros_to_ign( diff --git a/ros_ign_bridge/package.xml b/ros_ign_bridge/package.xml index 994c3ce8..bcab6df3 100644 --- a/ros_ign_bridge/package.xml +++ b/ros_ign_bridge/package.xml @@ -18,7 +18,6 @@ rclcpp ros_ign_interfaces rosgraph_msgs - ros_ign_interfaces sensor_msgs std_msgs tf2_msgs diff --git a/ros_ign_bridge/src/convert.cpp b/ros_ign_bridge/src/convert.cpp index a4a38136..0fa81246 100644 --- a/ros_ign_bridge/src/convert.cpp +++ b/ros_ign_bridge/src/convert.cpp @@ -50,34 +50,6 @@ std::string frame_id_ign_to_ros(const std::string & frame_id) return replace_delimiter(frame_id, "::", "/"); } -template<> -void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Color & ros_msg, - ignition::msgs::Color & ign_msg) -{ - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - - ign_msg.set_r(ros_msg.r); - ign_msg.set_g(ros_msg.g); - ign_msg.set_b(ros_msg.b); - ign_msg.set_a(ros_msg.a); -} - -template<> -void -convert_ign_to_ros( - const ignition::msgs::Color & ign_msg, - ros_ign_interfaces::msg::Color & ros_msg) -{ - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - - ros_msg.r = ign_msg.r(); - ros_msg.g = ign_msg.g(); - ros_msg.b = ign_msg.b(); - ros_msg.a = ign_msg.a(); -} - template<> void convert_ros_to_ign( @@ -156,6 +128,30 @@ convert_ign_to_ros( ros_msg.intensity = ign_msg.intensity(); } +template<> +void +convert_ros_to_ign( + const std_msgs::msg::ColorRGBA & ros_msg, + ignition::msgs::Color & ign_msg) +{ + ign_msg.set_r(ros_msg.r); + ign_msg.set_g(ros_msg.g); + ign_msg.set_b(ros_msg.b); + ign_msg.set_a(ros_msg.a); +} + +template<> +void +convert_ign_to_ros( + const ignition::msgs::Color & ign_msg, + std_msgs::msg::ColorRGBA & ros_msg) +{ + ros_msg.r = ign_msg.r(); + ros_msg.g = ign_msg.g(); + ros_msg.b = ign_msg.b(); + ros_msg.a = ign_msg.a(); +} + template<> void convert_ros_to_ign( diff --git a/ros_ign_bridge/src/factories.cpp b/ros_ign_bridge/src/factories.cpp index cb4d8cae..ab1dddf8 100644 --- a/ros_ign_bridge/src/factories.cpp +++ b/ros_ign_bridge/src/factories.cpp @@ -27,16 +27,6 @@ get_factory_impl( const std::string & ign_type_name) { // mapping from string to specialized template - if ((ros_type_name == "ros_ign_interfaces/msg/Color" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.Color") - { - return std::make_shared< - Factory< - ros_ign_interfaces::msg::Color, - ignition::msgs::Color - > - >("ros_ign_interfaces/msg/Color", ign_type_name); - } if ((ros_type_name == "ros_ign_interfaces/msg/Light" || ros_type_name.empty()) && ign_type_name == "ignition.msgs.Light") { @@ -47,6 +37,16 @@ get_factory_impl( > >("ros_ign_interfaces/msg/Light", ign_type_name); } + if ((ros_type_name == "std_msgs/msg/ColorRGBA" || + ros_type_name.empty()) && ign_type_name == "ignition.msgs.Color") + { + return std::make_shared< + Factory< + std_msgs::msg::ColorRGBA, + ignition::msgs::Color + > + >("std_msgs/msg/ColorRGBA", ign_type_name); + } if ((ros_type_name == "std_msgs/msg/Bool" || ros_type_name.empty()) && ign_type_name == "ignition.msgs.Boolean") { @@ -429,11 +429,11 @@ get_factory( template<> void Factory< - ros_ign_interfaces::msg::Color, - ignition::msgs::Color + ros_ign_interfaces::msg::Light, + ignition::msgs::Light >::convert_ros_to_ign( - const ros_ign_interfaces::msg::Color & ros_msg, - ignition::msgs::Color & ign_msg) + const ros_ign_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & ign_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -441,23 +441,24 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Color, - ignition::msgs::Color + ros_ign_interfaces::msg::Light, + ignition::msgs::Light >::convert_ign_to_ros( - const ignition::msgs::Color & ign_msg, - ros_ign_interfaces::msg::Color & ros_msg) + const ignition::msgs::Light & ign_msg, + ros_ign_interfaces::msg::Light & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } +// std_msgs template<> void Factory< - ros_ign_interfaces::msg::Light, - ignition::msgs::Light + std_msgs::msg::ColorRGBA, + ignition::msgs::Color >::convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg) + const std_msgs::msg::ColorRGBA & ros_msg, + ignition::msgs::Color & ign_msg) { ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); } @@ -465,16 +466,15 @@ Factory< template<> void Factory< - ros_ign_interfaces::msg::Light, - ignition::msgs::Light + std_msgs::msg::ColorRGBA, + ignition::msgs::Color >::convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg) + const ignition::msgs::Color & ign_msg, + std_msgs::msg::ColorRGBA & ros_msg) { ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); } -// std_msgs template<> void Factory< diff --git a/ros_ign_bridge/src/factories.hpp b/ros_ign_bridge/src/factories.hpp index 674b439b..b214c0d9 100644 --- a/ros_ign_bridge/src/factories.hpp +++ b/ros_ign_bridge/src/factories.hpp @@ -52,7 +52,6 @@ // Ignition messages #include -#include #include #include @@ -73,40 +72,40 @@ get_factory( template<> void Factory< - ros_ign_interfaces::msg::Color, - ignition::msgs::Color + ros_ign_interfaces::msg::Light, + ignition::msgs::Light >::convert_ros_to_ign( - const ros_ign_interfaces::msg::Color & ros_msg, - ignition::msgs::Color & ign_msg); + const ros_ign_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & ign_msg); template<> void Factory< - ros_ign_interfaces::msg::Color, - ignition::msgs::Color + ros_ign_interfaces::msg::Light, + ignition::msgs::Light >::convert_ign_to_ros( - const ignition::msgs::Color & ign_msg, - ros_ign_interfaces::msg::Color & ros_msg); + const ignition::msgs::Light & ign_msg, + ros_ign_interfaces::msg::Light & ros_msg); +// std_msgs template<> void Factory< - ros_ign_interfaces::msg::Light, - ignition::msgs::Light + std_msgs::msg::ColorRGBA, + ignition::msgs::Color >::convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg); + const std_msgs::msg::ColorRGBA & ros_msg, + ignition::msgs::Color & ign_msg); template<> void Factory< - ros_ign_interfaces::msg::Light, - ignition::msgs::Light + std_msgs::msg::ColorRGBA, + ignition::msgs::Color >::convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg); + const ignition::msgs::Color & ign_msg, + std_msgs::msg::ColorRGBA & ros_msg); -// std_msgs template<> void Factory< diff --git a/ros_ign_interfaces/CMakeLists.txt b/ros_ign_interfaces/CMakeLists.txt index f7f58789..7c40b036 100644 --- a/ros_ign_interfaces/CMakeLists.txt +++ b/ros_ign_interfaces/CMakeLists.txt @@ -16,7 +16,6 @@ find_package(geometry_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) set(msg_files - "msg/Color.msg" "msg/Contact.msg" "msg/Contacts.msg" "msg/Entity.msg" diff --git a/ros_ign_interfaces/msg/Color.msg b/ros_ign_interfaces/msg/Color.msg deleted file mode 100644 index 82c8d3d5..00000000 --- a/ros_ign_interfaces/msg/Color.msg +++ /dev/null @@ -1,6 +0,0 @@ -std_msgs/Header header - -float32 r # Red component -float32 g # Green component -float32 b # Blue component -float32 a # Alpha component diff --git a/ros_ign_interfaces/msg/Light.msg b/ros_ign_interfaces/msg/Light.msg index 1aae29d8..8f248518 100644 --- a/ros_ign_interfaces/msg/Light.msg +++ b/ros_ign_interfaces/msg/Light.msg @@ -10,8 +10,8 @@ uint8 DIRECTIONAL = 2 uint8 type geometry_msgs/Pose pose -ros_ign_interfaces/Color diffuse -ros_ign_interfaces/Color specular +std_msgs/ColorRGBA diffuse +std_msgs/ColorRGBA specular float32 attenuation_constant float32 attenuation_linear float32 attenuation_quadratic From f163fdd849db1dc25d9c14a2655147cb28dd56ee Mon Sep 17 00:00:00 2001 From: William Lew Date: Fri, 10 Dec 2021 16:11:14 -0800 Subject: [PATCH 08/15] Added tests for Light message Signed-off-by: William Lew --- ros_ign_bridge/README.md | 2 + .../include/ros_ign_bridge/convert.hpp | 1 + ros_ign_bridge/src/factories.hpp | 1 + .../test/launch/test_ign_subscriber.launch.py | 2 + .../test/launch/test_ros_subscriber.launch.py | 2 + .../test/publishers/ros_publisher.cpp | 15 ++++ .../test/subscribers/ros_subscriber.cpp | 26 ++++++ ros_ign_bridge/test/test_utils.hpp | 86 +++++++++++++++++++ ros_ign_image/CMakeLists.txt | 1 - ros_ign_interfaces/README.md | 5 +- ros_ign_interfaces/msg/Light.msg | 36 ++++---- 11 files changed, 156 insertions(+), 21 deletions(-) diff --git a/ros_ign_bridge/README.md b/ros_ign_bridge/README.md index 27227780..f06f0cdc 100644 --- a/ros_ign_bridge/README.md +++ b/ros_ign_bridge/README.md @@ -9,6 +9,7 @@ service calls. Its support is limited to only the following message types: | ROS type | Ignition Transport type | |--------------------------------------|:------------------------------------:| | std_msgs/msg/Bool | ignition::msgs::Boolean | +| std_msgs/msg/ColorRGBA | ignition::msgs::Color | | std_msgs/msg/Empty | ignition::msgs::Empty | | std_msgs/msg/Float32 | ignition::msgs::Float | | std_msgs/msg/Float64 | ignition::msgs::Double | @@ -31,6 +32,7 @@ service calls. Its support is limited to only the following message types: | ros_ign_interfaces/msg/Contacts | ignition::msgs::Contacts | | ros_ign_interfaces/msg/Entity | ignition::msgs::Entity | | ros_ign_interfaces/msg/JointWrench | ignition::msgs::JointWrench | +| ros_ign_interfaces/msg/Light | ignition::msgs::Light | | rosgraph_msgs/msg/Clock | ignition::msgs::Clock | | sensor_msgs/msg/BatteryState | ignition::msgs::BatteryState | | sensor_msgs/msg/CameraInfo | ignition::msgs::CameraInfo | diff --git a/ros_ign_bridge/include/ros_ign_bridge/convert.hpp b/ros_ign_bridge/include/ros_ign_bridge/convert.hpp index 88e48ae6..b908137d 100644 --- a/ros_ign_bridge/include/ros_ign_bridge/convert.hpp +++ b/ros_ign_bridge/include/ros_ign_bridge/convert.hpp @@ -42,6 +42,7 @@ #include #include #include +#include #include #include #include diff --git a/ros_ign_bridge/src/factories.hpp b/ros_ign_bridge/src/factories.hpp index b214c0d9..36edfeee 100644 --- a/ros_ign_bridge/src/factories.hpp +++ b/ros_ign_bridge/src/factories.hpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include diff --git a/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py b/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py index 20c98fd3..216dbf74 100644 --- a/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py +++ b/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py @@ -40,6 +40,7 @@ def generate_test_description(): executable='parameter_bridge', arguments=[ '/bool@std_msgs/msg/Bool@ignition.msgs.Boolean', + '/color@std_msgs/msg/ColorRGBA@ignition.msgs.Color', '/empty@std_msgs/msg/Empty@ignition.msgs.Empty', '/float@std_msgs/msg/Float32@ignition.msgs.Float', '/double@std_msgs/msg/Float64@ignition.msgs.Double', @@ -61,6 +62,7 @@ def generate_test_description(): '/entity@ros_ign_interfaces/msg/Entity@ignition.msgs.Entity', '/contact@ros_ign_interfaces/msg/Contact@ignition.msgs.Contact', '/contacts@ros_ign_interfaces/msg/Contacts@ignition.msgs.Contacts', + '/light@ros_ign_interfaces/msg/Light@ignition.msgs.Light', '/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo', '/fluid_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure', diff --git a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py index d6e9d42d..c0eac73e 100644 --- a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py +++ b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py @@ -40,6 +40,7 @@ def generate_test_description(): executable='parameter_bridge', arguments=[ '/bool@std_msgs/msg/Bool@ignition.msgs.Boolean', + '/color@std_msgs/msg/ColorRGBA@ignition.msgs.Color', '/empty@std_msgs/msg/Empty@ignition.msgs.Empty', '/float@std_msgs/msg/Float32@ignition.msgs.Float', '/double@std_msgs/msg/Float64@ignition.msgs.Double', @@ -61,6 +62,7 @@ def generate_test_description(): '/entity@ros_ign_interfaces/msg/Entity@ignition.msgs.Entity', '/contact@ros_ign_interfaces/msg/Contact@ignition.msgs.Contact', '/contacts@ros_ign_interfaces/msg/Contacts@ignition.msgs.Contacts', + '/light@ros_ign_interfaces/msg/Light@ignition.msgs.Light', '/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo', '/fluid_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure', diff --git a/ros_ign_bridge/test/publishers/ros_publisher.cpp b/ros_ign_bridge/test/publishers/ros_publisher.cpp index 53096bd6..b1399b68 100644 --- a/ros_ign_bridge/test/publishers/ros_publisher.cpp +++ b/ros_ign_bridge/test/publishers/ros_publisher.cpp @@ -22,6 +22,7 @@ // #include #include #include +#include #include #include #include @@ -33,6 +34,7 @@ #include #include #include +#include #include #include #include @@ -49,6 +51,11 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("ros_string_publisher"); rclcpp::Rate loop_rate(1); + // std_msgs::msg::Color. + auto color_pub = node->create_publisher("color", 1000); + std_msgs::msg::ColorRGBA color_msg; + ros_ign_bridge::testing::createTestMsg(color_msg); + // std_msgs::msg::Bool. auto bool_pub = node->create_publisher("bool", 1000); std_msgs::msg::Bool bool_msg; @@ -148,6 +155,12 @@ int main(int argc, char ** argv) geometry_msgs::msg::Wrench wrench_msg; ros_ign_bridge::testing::createTestMsg(wrench_msg); + // ros_ign_interfaces::msg::Light. + auto light_pub = + node->create_publisher("light", 1000); + ros_ign_interfaces::msg::Light light_msg; + ros_ign_bridge::testing::createTestMsg(light_msg); + // ros_ign_interfaces::msg::JointWrench. auto joint_wrench_pub = node->create_publisher("joint_wrench", 1000); @@ -246,6 +259,7 @@ int main(int argc, char ** argv) while (rclcpp::ok()) { // Publish all messages. + color_pub->publish(color_msg); bool_pub->publish(bool_msg); empty_pub->publish(empty_msg); float_pub->publish(float_msg); @@ -264,6 +278,7 @@ int main(int argc, char ** argv) tf2_message_pub->publish(tf2_msg); twist_pub->publish(twist_msg); wrench_pub->publish(wrench_msg); + light_pub->publish(light_msg); joint_wrench_pub->publish(joint_wrench_msg); entity_pub->publish(entity_msg); contact_pub->publish(contact_msg); diff --git a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp index a967a7de..0084eb86 100644 --- a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp +++ b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp @@ -26,6 +26,7 @@ #include "geometry_msgs/msg/vector3.hpp" #include "nav_msgs/msg/odometry.hpp" #include "rclcpp/rclcpp.hpp" +#include "ros_ign_interfaces/msg/light.hpp" #include "rosgraph_msgs/msg/clock.hpp" #include "sensor_msgs/msg/battery_state.hpp" #include "sensor_msgs/msg/camera_info.hpp" @@ -37,6 +38,7 @@ #include "sensor_msgs/msg/magnetic_field.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/color_rgba.hpp" #include "std_msgs/msg/empty.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/header.hpp" @@ -84,6 +86,18 @@ class MyTestClass typename rclcpp::Subscription::SharedPtr sub; }; +///////////////////////////////////////////////// +TEST(ROSSubscriberTest, Bool) +{ + MyTestClass client("color"); + + using namespace std::chrono_literals; + ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + node, client.callbackExecuted, 10ms, 200); + + EXPECT_TRUE(client.callbackExecuted); +} + ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Bool) { @@ -300,6 +314,18 @@ TEST(ROSSubscriberTest, Wrench) EXPECT_TRUE(client.callbackExecuted); } +///////////////////////////////////////////////// +TEST(ROSSubscriberTest, JointWrench) +{ + MyTestClass client("light"); + + using namespace std::chrono_literals; + ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + node, client.callbackExecuted, 10ms, 200); + + EXPECT_TRUE(client.callbackExecuted); +} + ///////////////////////////////////////////////// TEST(ROSSubscriberTest, JointWrench) { diff --git a/ros_ign_bridge/test/test_utils.hpp b/ros_ign_bridge/test/test_utils.hpp index 4f4cc41f..55421532 100644 --- a/ros_ign_bridge/test/test_utils.hpp +++ b/ros_ign_bridge/test/test_utils.hpp @@ -23,6 +23,7 @@ #include #include +#include #include #include #include @@ -42,6 +43,7 @@ #include #include #include +#include #include #include #include @@ -117,6 +119,29 @@ void waitUntilBoolVarAndSpin( /// ROS test utils ////////////////////////////////////////////////// +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(std_msgs::msg::ColorRGBA & _msg) +{ + _msg.r = 0.2; + _msg.g = 0.4; + _msg.b = 0.6; + _msg.a = 0.8; +} + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg) +{ + std_msgs::msg::ColorRGBA expected_msg; + createTestMsg(expected_msg); + + EXPECT_FLOAT_EQ(expected_msg.r, _msg->r); + EXPECT_FLOAT_EQ(expected_msg.g, _msg->g); + EXPECT_FLOAT_EQ(expected_msg.b, _msg->b); + EXPECT_FLOAT_EQ(expected_msg.a, _msg->a); +} + /// \brief Create a message used for testing. /// \param[out] _msg The message populated. void createTestMsg(std_msgs::msg::Bool & _msg) @@ -1129,6 +1154,67 @@ void compareTestMsg(const std::shared_ptr /// Ignition::msgs test utils ////////////////////////////////////////////////// +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(ros_ign_interfaces::msg::Light & _msg) +{ + createTestMsg(_msg.header); + + _msg.name = "test_light"; + _msg.type = 1; + + createTestMsg(_msg.pose); + createTestMsg(_msg.diffuse); + createTestMsg(_msg.specular); + _msg.attenuation_constant = 0.2; + _msg.attenuation_linear = 0.4; + _msg.attenuation_quadratic = 0.6; + createTestMsg(_msg.direction); + _msg.range = 25.0; + _msg.cast_shadows = true; + _msg.spot_inner_angle = 0.3; + _msg.spot_outer_angle = 0.6; + _msg.spot_falloff = 10.0; + + _msg.id = 24; + + _msg.parent_id = 6; + + _msg.intensity = 125.0; +} + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg) +{ + ros_ign_interfaces::msg::Light expected_msg; + createTestMsg(expected_msg); + + compareTestMsg(_msg->header); + + EXPECT_EQ(expected_msg.name, _msg->name); + EXPECT_EQ(expected_msg.type, _msg->type); + + compareTestMsg(std::make_shared(_msg->pose)); + compareTestMsg(std::make_shared(_msg->diffuse)); + compareTestMsg(std::make_shared(_msg->specular)); + EXPECT_FLOAT_EQ(expected_msg.attenuation_constant, _msg->attenuation_constant); + EXPECT_FLOAT_EQ(expected_msg.attenuation_linear, _msg->attenuation_linear); + EXPECT_FLOAT_EQ(expected_msg.attenuation_quadratic, _msg->attenuation_quadratic); + compareTestMsg(std::make_shared(_msg->direction)); + EXPECT_FLOAT_EQ(expected_msg.range, _msg->range); + EXPECT_EQ(expected_msg.cast_shadows, _msg->cast_shadows); + EXPECT_FLOAT_EQ(expected_msg.spot_inner_angle, _msg->spot_inner_angle); + EXPECT_FLOAT_EQ(expected_msg.spot_outer_angle, _msg->spot_outer_angle); + EXPECT_FLOAT_EQ(expected_msg.spot_falloff, _msg->spot_falloff); + + EXPECT_EQ(expected_msg.id, _msg->id); + + EXPECT_EQ(expected_msg.parent_id, _msg->parent_id); + + EXPECT_FLOAT_EQ(expected_msg.intensity, _msg->intensity); +} + /// \brief Create a message used for testing. /// \param[out] _msg The message populated. void createTestMsg(ignition::msgs::Boolean & _msg) diff --git a/ros_ign_image/CMakeLists.txt b/ros_ign_image/CMakeLists.txt index 57d75607..30787476 100644 --- a/ros_ign_image/CMakeLists.txt +++ b/ros_ign_image/CMakeLists.txt @@ -13,7 +13,6 @@ endif() find_package(ament_cmake REQUIRED) find_package(image_transport REQUIRED) find_package(ros_ign_bridge REQUIRED) -find_package(ros_ign_interfaces REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) diff --git a/ros_ign_interfaces/README.md b/ros_ign_interfaces/README.md index 82731d3c..f2cd7147 100644 --- a/ros_ign_interfaces/README.md +++ b/ros_ign_interfaces/README.md @@ -5,10 +5,11 @@ This package currently contains some Ignition-specific ROS message and service d ## Messages (.msg) * [Contact](msg/Contact.msg): related to [ignition::msgs::Contact](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contact.proto). Contant info bewteen collisions in Ignition Gazebo. -* [Contacts](msg/Contacts.msg): related to [ignition::msgs::Contacts](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contacts.proto).a list of contact. +* [Contacts](msg/Contacts.msg): related to [ignition::msgs::Contacts](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contacts.proto). A list of contacts. * [Entity](msg/Entity.msg): related to [ignition::msgs::Entity](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity.proto). Entity of Ignition Gazebo. * [EntityFactory](msg/EntityFactory.msg): related to [ignition::msgs::EntityFactory](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity_factory.proto). Message to create a new entity. -* [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Ingition Gazebo. +* [Light](msg/Light.msg): related to [ignition::msgs::Light](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/light.proto). Light info in Ignition Gazebo. +* [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Ignition Gazebo. * [WorldReset](msg/WorldReset.msg): related to [ignition::msgs::WorldReset](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_reset.proto). Reset time and model of simulation. ## Services (.srv) diff --git a/ros_ign_interfaces/msg/Light.msg b/ros_ign_interfaces/msg/Light.msg index 8f248518..911e20bd 100644 --- a/ros_ign_interfaces/msg/Light.msg +++ b/ros_ign_interfaces/msg/Light.msg @@ -1,29 +1,29 @@ -std_msgs/Header header +std_msgs/Header header # Optional header data -string name +string name # Light name # Light type: constant definition uint8 POINT = 0 uint8 SPOT = 1 uint8 DIRECTIONAL = 2 -uint8 type +uint8 type # Light type (from constant definitions) -geometry_msgs/Pose pose -std_msgs/ColorRGBA diffuse -std_msgs/ColorRGBA specular -float32 attenuation_constant -float32 attenuation_linear -float32 attenuation_quadratic -geometry_msgs/Vector3 direction -float32 range -bool cast_shadows -float32 spot_inner_angle -float32 spot_outer_angle -float32 spot_falloff +geometry_msgs/Pose pose # Light pose +std_msgs/ColorRGBA diffuse # Light diffuse emission +std_msgs/ColorRGBA specular # Light specular emission +float32 attenuation_constant # Constant variable in attenuation formula +float32 attenuation_linear # Linear variable in attenuation formula +float32 attenuation_quadratic # Quadratic variable in attenuation formula +geometry_msgs/Vector3 direction # Light direction +float32 range # Light range +bool cast_shadows # Enable/disable shadow casting +float32 spot_inner_angle # Spotlight inner cone angle +float32 spot_outer_angle # Spotlight outer cone angle +float32 spot_falloff # Falloff between inner and outer cone -uint32 id +uint32 id # Unique id of the light -uint32 parent_id +uint32 parent_id # Unique id of the light's parent -float32 intensity +float32 intensity # Light intensity From 707c80081e7e3006cea76b010b1bcd051643a179 Mon Sep 17 00:00:00 2001 From: William Lew Date: Tue, 21 Dec 2021 14:42:04 -0800 Subject: [PATCH 09/15] Fixed duplicated test name Signed-off-by: William Lew --- ros_ign_bridge/test/subscribers/ros_subscriber.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp index f2a4f4bd..b4437043 100644 --- a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp +++ b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp @@ -315,7 +315,7 @@ TEST(ROSSubscriberTest, Wrench) } ///////////////////////////////////////////////// -TEST(ROSSubscriberTest, JointWrench) +TEST(ROSSubscriberTest, Light) { MyTestClass client("light"); From 24b982edf022847e9d46c030a817822ec0480ecc Mon Sep 17 00:00:00 2001 From: William Lew Date: Tue, 21 Dec 2021 14:42:04 -0800 Subject: [PATCH 10/15] Fixed duplicated test name Signed-off-by: William Lew --- ros_ign_bridge/test/subscribers/ros_subscriber.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp index f2a4f4bd..656e7e0e 100644 --- a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp +++ b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp @@ -87,7 +87,7 @@ class MyTestClass }; ///////////////////////////////////////////////// -TEST(ROSSubscriberTest, Bool) +TEST(ROSSubscriberTest, Color) { MyTestClass client("color"); @@ -315,7 +315,7 @@ TEST(ROSSubscriberTest, Wrench) } ///////////////////////////////////////////////// -TEST(ROSSubscriberTest, JointWrench) +TEST(ROSSubscriberTest, Light) { MyTestClass client("light"); From d9336f697c5d5c63b73325d509b0942dcfe8203e Mon Sep 17 00:00:00 2001 From: William Lew Date: Wed, 22 Dec 2021 10:14:24 -0800 Subject: [PATCH 11/15] Fixed Light and Color tests Signed-off-by: William Lew --- .../test/publishers/ign_publisher.cpp | 12 ++ ros_ign_bridge/test/test_utils.hpp | 194 +++++++++++++----- 2 files changed, 157 insertions(+), 49 deletions(-) diff --git a/ros_ign_bridge/test/publishers/ign_publisher.cpp b/ros_ign_bridge/test/publishers/ign_publisher.cpp index bbb2a123..0081d17e 100644 --- a/ros_ign_bridge/test/publishers/ign_publisher.cpp +++ b/ros_ign_bridge/test/publishers/ign_publisher.cpp @@ -48,6 +48,16 @@ int main(int /*argc*/, char **/*argv*/) // Create a transport node and advertise a topic. ignition::transport::Node node; + // ignition::msgs::Color. + auto color_pub = node.Advertise("color"); + ignition::msgs::Color color_msg; + ros_ign_bridge::testing::createTestMsg(color_msg); + + // ignition::msgs::Light. + auto light_pub = node.Advertise("light"); + ignition::msgs::Light light_msg; + ros_ign_bridge::testing::createTestMsg(light_msg); + // ignition::msgs::Boolean. auto bool_pub = node.Advertise("bool"); ignition::msgs::Boolean bool_msg; @@ -224,6 +234,8 @@ int main(int /*argc*/, char **/*argv*/) // Publish messages at 1Hz. while (!g_terminatePub) { + color_pub.Publish(color_msg); + light_pub.Publish(light_msg); bool_pub.Publish(bool_msg); empty_pub.Publish(empty_msg); float_pub.Publish(float_msg); diff --git a/ros_ign_bridge/test/test_utils.hpp b/ros_ign_bridge/test/test_utils.hpp index 55df1951..e37a321c 100644 --- a/ros_ign_bridge/test/test_utils.hpp +++ b/ros_ign_bridge/test/test_utils.hpp @@ -527,6 +527,67 @@ void createTestMsg(ros_ign_interfaces::msg::JointWrench & _msg) createTestMsg(_msg.body_2_wrench); } +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(ros_ign_interfaces::msg::Light & _msg) +{ + createTestMsg(_msg.header); + + _msg.name = "test_light"; + _msg.type = 1; + + createTestMsg(_msg.pose); + createTestMsg(_msg.diffuse); + createTestMsg(_msg.specular); + _msg.attenuation_constant = 0.2; + _msg.attenuation_linear = 0.4; + _msg.attenuation_quadratic = 0.6; + createTestMsg(_msg.direction); + _msg.range = 25.0; + _msg.cast_shadows = true; + _msg.spot_inner_angle = 0.3; + _msg.spot_outer_angle = 0.6; + _msg.spot_falloff = 10.0; + + _msg.id = 24; + + _msg.parent_id = 6; + + _msg.intensity = 125.0; +} + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg) +{ + ros_ign_interfaces::msg::Light expected_msg; + createTestMsg(expected_msg); + + compareTestMsg(_msg->header); + + EXPECT_EQ(expected_msg.name, _msg->name); + EXPECT_EQ(expected_msg.type, _msg->type); + + compareTestMsg(std::make_shared(_msg->pose)); + compareTestMsg(std::make_shared(_msg->diffuse)); + compareTestMsg(std::make_shared(_msg->specular)); + EXPECT_FLOAT_EQ(expected_msg.attenuation_constant, _msg->attenuation_constant); + EXPECT_FLOAT_EQ(expected_msg.attenuation_linear, _msg->attenuation_linear); + EXPECT_FLOAT_EQ(expected_msg.attenuation_quadratic, _msg->attenuation_quadratic); + compareTestMsg(std::make_shared(_msg->direction)); + EXPECT_FLOAT_EQ(expected_msg.range, _msg->range); + EXPECT_EQ(expected_msg.cast_shadows, _msg->cast_shadows); + EXPECT_FLOAT_EQ(expected_msg.spot_inner_angle, _msg->spot_inner_angle); + EXPECT_FLOAT_EQ(expected_msg.spot_outer_angle, _msg->spot_outer_angle); + EXPECT_FLOAT_EQ(expected_msg.spot_falloff, _msg->spot_falloff); + + EXPECT_EQ(expected_msg.id, _msg->id); + + EXPECT_EQ(expected_msg.parent_id, _msg->parent_id); + + EXPECT_FLOAT_EQ(expected_msg.intensity, _msg->intensity); +} + /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. void compareTestMsg(const std::shared_ptr & _msg) @@ -1140,63 +1201,25 @@ void compareTestMsg(const std::shared_ptr /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Light & _msg) +void createTestMsg(ignition::msgs::Color & _msg) { - createTestMsg(_msg.header); - - _msg.name = "test_light"; - _msg.type = 1; - - createTestMsg(_msg.pose); - createTestMsg(_msg.diffuse); - createTestMsg(_msg.specular); - _msg.attenuation_constant = 0.2; - _msg.attenuation_linear = 0.4; - _msg.attenuation_quadratic = 0.6; - createTestMsg(_msg.direction); - _msg.range = 25.0; - _msg.cast_shadows = true; - _msg.spot_inner_angle = 0.3; - _msg.spot_outer_angle = 0.6; - _msg.spot_falloff = 10.0; - - _msg.id = 24; - - _msg.parent_id = 6; - - _msg.intensity = 125.0; + _msg.set_r(0.2); + _msg.set_g(0.4); + _msg.set_b(0.6); + _msg.set_a(0.8); } /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Light expected_msg; + ignition::msgs::Color expected_msg; createTestMsg(expected_msg); - compareTestMsg(_msg->header); - - EXPECT_EQ(expected_msg.name, _msg->name); - EXPECT_EQ(expected_msg.type, _msg->type); - - compareTestMsg(std::make_shared(_msg->pose)); - compareTestMsg(std::make_shared(_msg->diffuse)); - compareTestMsg(std::make_shared(_msg->specular)); - EXPECT_FLOAT_EQ(expected_msg.attenuation_constant, _msg->attenuation_constant); - EXPECT_FLOAT_EQ(expected_msg.attenuation_linear, _msg->attenuation_linear); - EXPECT_FLOAT_EQ(expected_msg.attenuation_quadratic, _msg->attenuation_quadratic); - compareTestMsg(std::make_shared(_msg->direction)); - EXPECT_FLOAT_EQ(expected_msg.range, _msg->range); - EXPECT_EQ(expected_msg.cast_shadows, _msg->cast_shadows); - EXPECT_FLOAT_EQ(expected_msg.spot_inner_angle, _msg->spot_inner_angle); - EXPECT_FLOAT_EQ(expected_msg.spot_outer_angle, _msg->spot_outer_angle); - EXPECT_FLOAT_EQ(expected_msg.spot_falloff, _msg->spot_falloff); - - EXPECT_EQ(expected_msg.id, _msg->id); - - EXPECT_EQ(expected_msg.parent_id, _msg->parent_id); - - EXPECT_FLOAT_EQ(expected_msg.intensity, _msg->intensity); + EXPECT_EQ(expected_msg.r(), _msg->r()); + EXPECT_EQ(expected_msg.g(), _msg->g()); + EXPECT_EQ(expected_msg.b(), _msg->b()); + EXPECT_EQ(expected_msg.a(), _msg->a()); } /// \brief Create a message used for testing. @@ -2229,6 +2252,79 @@ void compareTestMsg(const std::shared_ptr & _ms } } +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(ignition::msgs::Light & _msg) +{ + ignition::msgs::Header header_msg; + ignition::msgs::Pose pose_msg; + ignition::msgs::Color diffuse_msg; + ignition::msgs::Color specular_msg; + ignition::msgs::Vector3d direction_msg; + + createTestMsg(header_msg); + createTestMsg(pose_msg); + createTestMsg(diffuse_msg); + createTestMsg(specular_msg); + createTestMsg(direction_msg); + + _msg.mutable_header()->CopyFrom(header_msg); + _msg.mutable_pose()->CopyFrom(pose_msg); + _msg.mutable_diffuse()->CopyFrom(diffuse_msg); + _msg.mutable_specular()->CopyFrom(specular_msg); + _msg.mutable_direction()->CopyFrom(direction_msg); + + _msg.set_name("test_light"); + _msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT); + + _msg.set_attenuation_constant(0.2); + _msg.set_attenuation_linear(0.4); + _msg.set_attenuation_quadratic(0.6); + _msg.set_range(25.0); + _msg.set_cast_shadows(true); + _msg.set_spot_inner_angle(0.3); + _msg.set_spot_outer_angle(0.6); + _msg.set_spot_falloff(10.0); + + _msg.set_id(24); + + _msg.set_parent_id(6); + + _msg.set_intensity(125.0); +} + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg) +{ + ignition::msgs::Light expected_msg; + createTestMsg(expected_msg); + + compareTestMsg(std::make_shared(_msg->header())); + compareTestMsg(std::make_shared(_msg->pose())); + compareTestMsg(std::make_shared(_msg->diffuse())); + compareTestMsg(std::make_shared(_msg->specular())); + compareTestMsg(std::make_shared(_msg->direction())); + + EXPECT_EQ(expected_msg.name(), _msg->name()); + EXPECT_EQ(expected_msg.type(), _msg->type()); + + EXPECT_FLOAT_EQ(expected_msg.attenuation_constant(), _msg->attenuation_constant()); + EXPECT_FLOAT_EQ(expected_msg.attenuation_linear(), _msg->attenuation_linear()); + EXPECT_FLOAT_EQ(expected_msg.attenuation_quadratic(), _msg->attenuation_quadratic()); + EXPECT_FLOAT_EQ(expected_msg.range(), _msg->range()); + EXPECT_EQ(expected_msg.cast_shadows(), _msg->cast_shadows()); + EXPECT_FLOAT_EQ(expected_msg.spot_inner_angle(), _msg->spot_inner_angle()); + EXPECT_FLOAT_EQ(expected_msg.spot_outer_angle(), _msg->spot_outer_angle()); + EXPECT_FLOAT_EQ(expected_msg.spot_falloff(), _msg->spot_falloff()); + + EXPECT_EQ(expected_msg.id(), _msg->id()); + + EXPECT_EQ(expected_msg.parent_id(), _msg->parent_id()); + + EXPECT_FLOAT_EQ(expected_msg.intensity(), _msg->intensity()); +} + } // namespace testing } // namespace ros_ign_bridge From 19e3c23af2ab3adc896fadd1f4825f7435270ca1 Mon Sep 17 00:00:00 2001 From: William Lew Date: Wed, 22 Dec 2021 10:39:40 -0800 Subject: [PATCH 12/15] Increased testing time Signed-off-by: William Lew --- ros_ign_bridge/test/launch/test_ign_subscriber.launch.py | 2 +- ros_ign_bridge/test/launch/test_ros_subscriber.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py b/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py index 216dbf74..9d3b298a 100644 --- a/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py +++ b/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py @@ -90,7 +90,7 @@ def generate_test_description(): class IgnSubscriberTest(unittest.TestCase): def test_termination(self, process_under_test, proc_info): - proc_info.assertWaitForShutdown(process=process_under_test, timeout=200) + proc_info.assertWaitForShutdown(process=process_under_test, timeout=500) @launch_testing.post_shutdown_test() diff --git a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py index 28ac4be4..ddd3c0f5 100644 --- a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py +++ b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py @@ -90,7 +90,7 @@ def generate_test_description(): class ROSSubscriberTest(unittest.TestCase): def test_termination(self, process_under_test, proc_info): - proc_info.assertWaitForShutdown(process=process_under_test, timeout=200) + proc_info.assertWaitForShutdown(process=process_under_test, timeout=500) @launch_testing.post_shutdown_test() From a300f18158d700933b72dd8d8f7f993d00bf5a02 Mon Sep 17 00:00:00 2001 From: William Lew Date: Wed, 22 Dec 2021 11:06:15 -0800 Subject: [PATCH 13/15] Fixed style errors Signed-off-by: William Lew --- ros_ign_bridge/src/convert.cpp | 15 +++++++-------- ros_ign_bridge/src/factories.cpp | 4 ++-- .../test/launch/test_ign_subscriber.launch.py | 2 +- .../test/launch/test_ros_subscriber.launch.py | 2 +- 4 files changed, 11 insertions(+), 12 deletions(-) diff --git a/ros_ign_bridge/src/convert.cpp b/ros_ign_bridge/src/convert.cpp index 0fa81246..e740d718 100644 --- a/ros_ign_bridge/src/convert.cpp +++ b/ros_ign_bridge/src/convert.cpp @@ -65,7 +65,7 @@ convert_ros_to_ign( ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT); } else if (ros_msg.type == 2) { ign_msg.set_type( - ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL); + ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL); } convert_ros_to_ign(ros_msg.pose, *ign_msg.mutable_pose()); @@ -98,13 +98,12 @@ convert_ign_to_ros( ros_msg.name = ign_msg.name(); if (ign_msg.type() == - ignition::msgs::Light_LightType::Light_LightType_POINT) { + ignition::msgs::Light_LightType::Light_LightType_POINT) + { ros_msg.type = 0; - } else if (ign_msg.type() == - ignition::msgs::Light_LightType::Light_LightType_SPOT) { + } else if (ign_msg.type() == ignition::msgs::Light_LightType::Light_LightType_SPOT) { ros_msg.type = 1; - } else if (ign_msg.type() == - ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL) { + } else if (ign_msg.type() == ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL) { ros_msg.type = 2; } @@ -122,9 +121,9 @@ convert_ign_to_ros( ros_msg.spot_falloff = ign_msg.spot_falloff(); ros_msg.id = ign_msg.id(); - + ros_msg.parent_id = ign_msg.parent_id(); - + ros_msg.intensity = ign_msg.intensity(); } diff --git a/ros_ign_bridge/src/factories.cpp b/ros_ign_bridge/src/factories.cpp index ab1dddf8..74b8d188 100644 --- a/ros_ign_bridge/src/factories.cpp +++ b/ros_ign_bridge/src/factories.cpp @@ -27,7 +27,7 @@ get_factory_impl( const std::string & ign_type_name) { // mapping from string to specialized template - if ((ros_type_name == "ros_ign_interfaces/msg/Light" || + if ((ros_type_name == "ros_ign_interfaces/msg/Light" || ros_type_name.empty()) && ign_type_name == "ignition.msgs.Light") { return std::make_shared< @@ -37,7 +37,7 @@ get_factory_impl( > >("ros_ign_interfaces/msg/Light", ign_type_name); } - if ((ros_type_name == "std_msgs/msg/ColorRGBA" || + if ((ros_type_name == "std_msgs/msg/ColorRGBA" || ros_type_name.empty()) && ign_type_name == "ignition.msgs.Color") { return std::make_shared< diff --git a/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py b/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py index 9d3b298a..216dbf74 100644 --- a/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py +++ b/ros_ign_bridge/test/launch/test_ign_subscriber.launch.py @@ -90,7 +90,7 @@ def generate_test_description(): class IgnSubscriberTest(unittest.TestCase): def test_termination(self, process_under_test, proc_info): - proc_info.assertWaitForShutdown(process=process_under_test, timeout=500) + proc_info.assertWaitForShutdown(process=process_under_test, timeout=200) @launch_testing.post_shutdown_test() diff --git a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py index ddd3c0f5..28ac4be4 100644 --- a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py +++ b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py @@ -90,7 +90,7 @@ def generate_test_description(): class ROSSubscriberTest(unittest.TestCase): def test_termination(self, process_under_test, proc_info): - proc_info.assertWaitForShutdown(process=process_under_test, timeout=500) + proc_info.assertWaitForShutdown(process=process_under_test, timeout=200) @launch_testing.post_shutdown_test() From 99e49dbf52a5f79e4fb7ca6ca9b8a9ba81c9ca58 Mon Sep 17 00:00:00 2001 From: William Lew Date: Mon, 27 Dec 2021 10:34:15 -0800 Subject: [PATCH 14/15] Fixed formatting errors Signed-off-by: William Lew --- ros_ign_bridge/src/convert/sensor_msgs.cpp | 1 - ros_ign_bridge/src/factories.hpp | 1 - ros_ign_bridge/src/factory.hpp | 1 - 3 files changed, 3 deletions(-) diff --git a/ros_ign_bridge/src/convert/sensor_msgs.cpp b/ros_ign_bridge/src/convert/sensor_msgs.cpp index 537c163d..3da2265d 100644 --- a/ros_ign_bridge/src/convert/sensor_msgs.cpp +++ b/ros_ign_bridge/src/convert/sensor_msgs.cpp @@ -593,4 +593,3 @@ convert_ign_to_ros( } } // namespace ros_ign_bridge - diff --git a/ros_ign_bridge/src/factories.hpp b/ros_ign_bridge/src/factories.hpp index 22954897..ccb3a5f4 100644 --- a/ros_ign_bridge/src/factories.hpp +++ b/ros_ign_bridge/src/factories.hpp @@ -31,4 +31,3 @@ get_factory( } // namespace ros_ign_bridge #endif // FACTORIES_HPP_ - diff --git a/ros_ign_bridge/src/factory.hpp b/ros_ign_bridge/src/factory.hpp index 6ad87843..8ac13e60 100644 --- a/ros_ign_bridge/src/factory.hpp +++ b/ros_ign_bridge/src/factory.hpp @@ -163,4 +163,3 @@ class Factory : public FactoryInterface } // namespace ros_ign_bridge #endif // FACTORY_HPP_ - From 8735d1c7fc98e8b73c50362b701b397c2658dd55 Mon Sep 17 00:00:00 2001 From: William Lew Date: Mon, 27 Dec 2021 18:00:22 -0800 Subject: [PATCH 15/15] Added code suggestions Signed-off-by: William Lew --- ros_ign_bridge/CMakeLists.txt | 1 - ros_ign_image/CMakeLists.txt | 1 - 2 files changed, 2 deletions(-) diff --git a/ros_ign_bridge/CMakeLists.txt b/ros_ign_bridge/CMakeLists.txt index fc2d4dfe..a8d2752b 100644 --- a/ros_ign_bridge/CMakeLists.txt +++ b/ros_ign_bridge/CMakeLists.txt @@ -146,7 +146,6 @@ foreach(bridge ${bridge_executables}) ${bridge_lib} ignition-msgs${IGN_MSGS_VER}::core ignition-transport${IGN_TRANSPORT_VER}::core - ${bridge_lib} ) ament_target_dependencies(${bridge} "rclcpp" diff --git a/ros_ign_image/CMakeLists.txt b/ros_ign_image/CMakeLists.txt index 1e747a5b..0901ad9f 100644 --- a/ros_ign_image/CMakeLists.txt +++ b/ros_ign_image/CMakeLists.txt @@ -72,7 +72,6 @@ target_link_libraries(${executable} ament_target_dependencies(${executable} "image_transport" "ros_ign_bridge" - "ros_ign_interfaces" "rclcpp" "sensor_msgs" )