MapIV / eagleye

Precise localization based on GNSS and IMU.

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

ros2-foxy build error

cshang412 opened this issue · comments

Current branch main-ros2

~$ colcon build --packages-up-to eagleye_rt --symlink-install
Starting >>> geographic_msgs
Starting >>> rtklib_msgs
Starting >>> nmea_msgs
Finished <<< rtklib_msgs [0.59s]
Starting >>> eagleye_msgs
Finished <<< nmea_msgs [0.95s]
Finished <<< geographic_msgs [1.41s]
Starting >>> geodesy
Finished <<< geodesy [0.30s]
Starting >>> geographic_info
Finished <<< eagleye_msgs [1.22s]
Finished <<< geographic_info [0.19s]
Starting >>> eagleye_coordinate
Finished <<< eagleye_coordinate [0.27s]
Starting >>> eagleye_navigation
Finished <<< eagleye_navigation [0.43s]
Starting >>> eagleye_rt
[Processing: eagleye_rt]
[Processing: eagleye_rt]
--- stderr: eagleye_rt
In file included from /usr/include/c++/9/ext/alloc_traits.h:36,
from /usr/include/c++/9/bits/basic_string.h:40,
from /usr/include/c++/9/string:55,
from /usr/include/c++/9/bits/locale_classes.h:40,
from /usr/include/c++/9/bits/ios_base.h:41,
from /usr/include/c++/9/ios:42,
from /usr/include/c++/9/ostream:38,
from /usr/include/c++/9/iostream:39,
from /home/david/Documents/ros2/localization/gnss_imu/install/geodesy/include/geodesy/utm.h:43,
from /home/david/Documents/ros2/localization/gnss_imu/install/eagleye_coordinate/include/eagleye_coordinate/eagleye_coordinate.hpp:30,
from /home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:31:
/usr/include/c++/9/bits/alloc_traits.h: In instantiation of ‘struct std::allocator_traits<std::allocator<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&> >’:
/opt/ros/foxy/include/rclcpp/message_memory_strategy.hpp:47:9: required from ‘class rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >’
/opt/ros/foxy/include/rclcpp/node_impl.hpp:91:1: required by substitution of ‘template<class MessageT, class CallbackT, class AllocatorT, class CallbackMessageT, class SubscriptionT, class MessageMemoryStrategyT> std::shared_ptr rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = eagleye_msgs::msg::VelocityScaleFactor_<std::allocator >; CallbackT = void (&)(const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&); AllocatorT = std::allocator; CallbackMessageT = const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&; SubscriptionT = rclcpp::Subscription<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator, rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >]’
/home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:135:142: required from here
/usr/include/c++/9/bits/alloc_traits.h:399:13: error: forming pointer to reference type ‘const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&’
399 | using pointer = Tp*;
| ^~~~~~~
/usr/include/c++/9/bits/alloc_traits.h:402:13: error: forming pointer to reference type ‘const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor
<std::allocator > >&’
402 | using const_pointer = const Tp*;
| ^~~~~~~~~~~~~
In file included from /usr/include/c++/9/bits/locale_conv.h:41,
from /usr/include/c++/9/locale:43,
from /usr/include/c++/9/iomanip:43,
from /home/david/Documents/ros2/localization/gnss_imu/install/geodesy/include/geodesy/utm.h:44,
from /home/david/Documents/ros2/localization/gnss_imu/install/eagleye_coordinate/include/eagleye_coordinate/eagleye_coordinate.hpp:30,
from /home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:31:
/usr/include/c++/9/bits/unique_ptr.h: In instantiation of ‘struct std::default_delete<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor
<std::allocator > >&>’:
/opt/ros/foxy/include/rclcpp/message_memory_strategy.hpp:119:18: required from ‘class rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >’
/opt/ros/foxy/include/rclcpp/node_impl.hpp:91:1: required by substitution of ‘template<class MessageT, class CallbackT, class AllocatorT, class CallbackMessageT, class SubscriptionT, class MessageMemoryStrategyT> std::shared_ptr rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = eagleye_msgs::msg::VelocityScaleFactor_<std::allocator >; CallbackT = void (&)(const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&); AllocatorT = std::allocator; CallbackMessageT = const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&; SubscriptionT = rclcpp::Subscription<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator, rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >]’
/home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:135:142: required from here
/usr/include/c++/9/bits/unique_ptr.h:71:9: error: forming pointer to reference type ‘const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&’
71 | default_delete(const default_delete<_Up>&) noexcept { }

update: i got it, the issue was caused by callback function locate in enable_additional_rolling_node.cpp

For example:

Change all callback param from TypePtr to Ptr without reference,
Origin:

void velocity_scale_factor_callback(const eagleye_msgs::msg::VelocityScaleFactor::ConstPtr &msg) { _velocity_scale_factor = *msg; }

Changed

void velocity_scale_factor_callback(const eagleye_msgs::msg::VelocityScaleFactor::ConstSharedPtr msg) { _velocity_scale_factor = *msg; }

Thanks for the report. We will fix that bug.

Fixed a bug and added CI with ros foxy. Thanks for the report. Please contact me if you have any more problems.
Now that the problem has been resolved, close this issue.