Skip to content

Commit

Permalink
Merge pull request ApolloAuto#15541 from WildBeast114514/preview
Browse files Browse the repository at this point in the history
fix: build error and communication failed when using ros foxy or galatic
  • Loading branch information
WildBeast114514 authored Sep 24, 2024
2 parents 99432e6 + 83ba04f commit f460c50
Show file tree
Hide file tree
Showing 8 changed files with 145 additions and 79 deletions.
28 changes: 16 additions & 12 deletions cyber/ros_bridge/converter_base/convert_ros_double.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,13 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1) {
auto out = std::make_shared<OutType0>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
Expand Down Expand Up @@ -189,13 +190,14 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
Expand Down Expand Up @@ -295,14 +297,15 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
Expand Down Expand Up @@ -414,15 +417,16 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
auto out_3 = std::make_shared<OutType3>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>>{
std::make_tuple(internal_in_prt_0, internal_in_prt_1)};
Expand Down
56 changes: 32 additions & 24 deletions cyber/ros_bridge/converter_base/convert_ros_quadruple.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,17 +110,19 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2, const InType3& ros_msg3) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2,
std::shared_ptr<InType3> ros_msg3) {
auto out = std::make_shared<OutType0>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType2>(ros_msg2);
std::make_shared<InType2>(*ros_msg2.get());
typename InType3::SharedPtr internal_in_prt_3 =
std::make_shared<InType3>(ros_msg3);
std::make_shared<InType3>(*ros_msg3.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
Expand Down Expand Up @@ -229,18 +231,20 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2, const InType3& ros_msg3) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2,
std::shared_ptr<InType3> ros_msg3) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType2>(ros_msg2);
std::make_shared<InType2>(*ros_msg2.get());
typename InType3::SharedPtr internal_in_prt_3 =
std::make_shared<InType3>(ros_msg3);
std::make_shared<InType3>(*ros_msg3.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
Expand Down Expand Up @@ -359,19 +363,21 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2, const InType3& ros_msg3) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2,
std::shared_ptr<InType3> ros_msg3) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType2>(ros_msg2);
std::make_shared<InType2>(*ros_msg2.get());
typename InType3::SharedPtr internal_in_prt_3 =
std::make_shared<InType3>(ros_msg3);
std::make_shared<InType3>(*ros_msg3.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
Expand Down Expand Up @@ -502,20 +508,22 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2, const InType3& ros_msg3) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2,
std::shared_ptr<InType3> ros_msg3) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
auto out_3 = std::make_shared<OutType3>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType2>(ros_msg2);
std::make_shared<InType2>(*ros_msg2.get());
typename InType3::SharedPtr internal_in_prt_3 =
std::make_shared<InType3>(ros_msg3);
std::make_shared<InType3>(*ros_msg3.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>, std::shared_ptr<InType3>>{
Expand Down
16 changes: 8 additions & 8 deletions cyber/ros_bridge/converter_base/convert_ros_single.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,10 +75,10 @@ class RosApolloMessageConverter<InputTypes<std::shared_ptr<InType0>>,

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
auto out = std::make_shared<OutType0>();
typename InType0::SharedPtr internal_in_prt =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
auto out_container =
Expand Down Expand Up @@ -148,11 +148,11 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
typename InType0::SharedPtr internal_in_prt =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
auto out_container =
Expand Down Expand Up @@ -234,12 +234,12 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
typename InType0::SharedPtr internal_in_prt =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
auto out_container =
Expand Down Expand Up @@ -333,13 +333,13 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
auto out_3 = std::make_shared<OutType3>();
typename InType0::SharedPtr internal_in_prt =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>>{std::make_tuple(internal_in_prt)};
auto out_container =
Expand Down
44 changes: 24 additions & 20 deletions cyber/ros_bridge/converter_base/convert_ros_triple.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,15 +104,16 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2) {
auto out = std::make_shared<OutType0>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType2>(ros_msg2);
std::make_shared<InType2>(*ros_msg2.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>>{std::make_tuple(
Expand Down Expand Up @@ -214,16 +215,17 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType2>(ros_msg2);
std::make_shared<InType2>(*ros_msg2.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>>{std::make_tuple(
Expand Down Expand Up @@ -334,17 +336,18 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType2>(ros_msg2);
std::make_shared<InType2>(*ros_msg2.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>>{std::make_tuple(
Expand Down Expand Up @@ -467,18 +470,19 @@ class RosApolloMessageConverter<

#ifdef RCLCPP__RCLCPP_HPP_
private:
void TopicCallback(const InType0& ros_msg0, const InType1& ros_msg1,
const InType2& ros_msg2) {
void TopicCallback(std::shared_ptr<InType0> ros_msg0,
std::shared_ptr<InType1> ros_msg1,
std::shared_ptr<InType2> ros_msg2) {
auto out_0 = std::make_shared<OutType0>();
auto out_1 = std::make_shared<OutType1>();
auto out_2 = std::make_shared<OutType2>();
auto out_3 = std::make_shared<OutType3>();
typename InType0::SharedPtr internal_in_prt_0 =
std::make_shared<InType0>(ros_msg0);
std::make_shared<InType0>(*ros_msg0.get());
typename InType1::SharedPtr internal_in_prt_1 =
std::make_shared<InType1>(ros_msg1);
std::make_shared<InType1>(*ros_msg1.get());
typename InType2::SharedPtr internal_in_prt_2 =
std::make_shared<InType1>(ros_msg2);
std::make_shared<InType1>(*ros_msg2.get());
auto in_container =
InputTypes<std::shared_ptr<InType0>, std::shared_ptr<InType1>,
std::shared_ptr<InType2>>{std::make_tuple(
Expand Down
24 changes: 13 additions & 11 deletions cyber/ros_bridge/converter_base/message_converter.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/synchronizer.h"
#include "rclcpp/rclcpp.hpp"
#include "ros_distro.h"
#endif

namespace apollo {
Expand All @@ -46,12 +47,7 @@ class MessageConverter {
public:
MessageConverter() : init_(false) {}

virtual ~MessageConverter() {
#ifdef RCLCPP__RCLCPP_HPP_
delete ros_node_;
delete ros_node_exec_;
#endif
}
virtual ~MessageConverter() {}

virtual bool Init() {
if (init_.exchange(true)) {
Expand All @@ -61,9 +57,10 @@ class MessageConverter {
cyber_node_ = std::move(
CreateNode(node_name_ + "_" + converter_conf_.name() + "_apollo"));
#ifdef RCLCPP__RCLCPP_HPP_
ros_node_ =
new ::rclcpp::Node(node_name_ + "_" + converter_conf_.name() + "_ros");
ros_node_exec_ = new ::rclcpp::executors::SingleThreadedExecutor();
ros_node_ = std::make_shared<::rclcpp::Node>(
node_name_ + "_" + converter_conf_.name() + "_ros");
ros_node_exec_ =
std::make_shared<::rclcpp::executors::SingleThreadedExecutor>();
#endif
return true;
}
Expand Down Expand Up @@ -129,10 +126,15 @@ class MessageConverter {
#ifdef RCLCPP__RCLCPP_HPP_
std::vector<std::shared_ptr<::rclcpp::PublisherBase>> ros_publishers_;
std::vector<std::shared_ptr<::rclcpp::SubscriptionBase>> ros_subscriptions_;
#if defined(ROS_DISTRO_FOXY) || defined(ROS_DISTRO_GALACTIC)
std::vector<std::shared_ptr<::message_filters::SubscriberBase>>
#else
std::vector<std::shared_ptr<::message_filters::SubscriberBase<rclcpp::Node>>>
#endif
ros_msg_subs_;
::rclcpp::Node* ros_node_ = nullptr;
::rclcpp::executors::SingleThreadedExecutor* ros_node_exec_ = nullptr;
std::shared_ptr<::rclcpp::Node> ros_node_ = nullptr;
std::shared_ptr<::rclcpp::executors::SingleThreadedExecutor> ros_node_exec_ =
nullptr;
std::shared_ptr<std::thread> ros_spin_thread_;
#endif
const std::string node_name_ = "converter_base";
Expand Down
Loading

0 comments on commit f460c50

Please sign in to comment.