ROS Eloquent - Gazebo10 integration
Edit:
Compilation solved. Switch boost::bind()
to std::bind()
(#include _1
to std::placeholders::_1
I am failing to integrate a ROS node with a Gazebo10 plugin. I am following this tutorial more or less but translating to the ROS2 API: http://gazebosim.org/tutorials?cat=guided_i&tut=guided_i6 . It seems that there is something wrong in my declaration of a subscription. I can't upload my file because I don't have 5 points, but I have copied the relevant code. I do not want to use gazeborospkgs.
// Initialize ros, if it has not already been initialized
if (!rclcpp::is_initialized())
{
int argc = 0;
char** argv = NULL;
//rclcpp::init(argc, argv, rclcpp::init_options::NoSigintHandler);
rclcpp::init(argc, argv);
}
// Setup callback group
this->rosCallbackGroup = this->rosNode->create_callback_group(
rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
// Setup subscriber options
this->rosSubOptions = rclcpp::SubscriptionOptions();
this->rosSubOptions.callback_group = this->rosCallbackGroup;
// Setup subscriber
this->rosSub = this->rosNode->create_subscription<std_msgs::msg::Float32>(
"/" + this->model->GetName() + "/vel_cmd",
rclcpp::QoS(1),
boost::bind(&VelodynePlugin::OnRosMsg, this, _1),
this->rosSubOptions);
Generating the following error:
In file included from /opt/ros/eloquent/include/rclcpp/client.hpp:31:0,
from /opt/ros/eloquent/include/rclcpp/callback_group.hpp:23,
from /opt/ros/eloquent/include/rclcpp/any_executable.hpp:20,
from /opt/ros/eloquent/include/rclcpp/memory_strategy.hpp:24,
from /opt/ros/eloquent/include/rclcpp/memory_strategies.hpp:18,
from /opt/ros/eloquent/include/rclcpp/executor.hpp:33,
from /opt/ros/eloquent/include/rclcpp/executors/multi_threaded_executor.hpp:25,
from /opt/ros/eloquent/include/rclcpp/executors.hpp:21,
from /opt/ros/eloquent/include/rclcpp/rclcpp.hpp:145,
from /ros2-dev/gazebo/.gazebo/plugins/velodyne/velodyne_plugin.cc:8: /opt/ros/eloquent/include/rclcpp/function_traits.hpp: In instantiation of ‘struct rclcpp::function_traits::function_traits<boost::_bi::bind_t<void, boost::_mfi::mf1<void, gazebo::VelodynePlugin, std::shared_ptr<std_msgs::msg::Float32_<std::allocator<void>
> > >, boost::_bi::list2<boost::_bi::value<gazebo::VelodynePlugin*>, boost::arg<1> > > >’: /opt/ros/eloquent/include/rclcpp/subscription_traits.hpp:90:8: required from ‘struct rclcpp::subscription_traits::has_message_type<boost::_bi::bind_t<void, boost::_mfi::mf1<void, gazebo::VelodynePlugin, std::shared_ptr<std_msgs::msg::Float32_<std::allocator<void>
> > >, boost::_bi::list2<boost::_bi::value<gazebo::VelodynePlugin*>, boost::arg<1> > >, void, void, void>’ /opt/ros/eloquent/include/rclcpp/node.hpp:199:5: required by substitution of ‘template<class MessageT, class CallbackT, class AllocatorT, class CallbackMessageT, class SubscriptionT, class MessageMemoryStrategyT> std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = std_msgs::msg::Float32_<std::allocator<void>
>; CallbackT = boost::_bi::bind_t<void, boost::_mfi::mf1<void, gazebo::VelodynePlugin, std::shared_ptr<std_msgs::msg::Float32_<std::allocator<void>
> > >, boost::_bi::list2<boost::_bi::value<gazebo::VelodynePlugin*>, boost::arg<1> > >; AllocatorT = std::allocator<void>; CallbackMessageT
= <missing>; SubscriptionT = <missing>; MessageMemoryStrategyT = <missing>]’ /ros2-dev/gazebo/.gazebo/plugins/velodyne/velodyne_plugin.cc:128:32: required from here /opt/ros/eloquent/include/rclcpp/function_traits.hpp:52:82: error: decltype cannot resolve address of overloaded function
typename function_traits<decltype( &FunctionT::operator())>::arguments>::type;
^ /opt/ros/eloquent/include/rclcpp/function_traits.hpp:57:72: error: decltype cannot resolve address of overloaded function using argument_type = typename std::tuple_element<N, arguments>::type;
^ /opt/ros/eloquent/include/rclcpp/function_traits.hpp:59:95: error: decltype cannot resolve address of overloaded function using return_type = typename function_traits<decltype( &FunctionT::operator())>::return_type;
^ /ros2-dev/gazebo/.gazebo/plugins/velodyne/velodyne_plugin.cc: In member function ‘void gazebo::VelodynePlugin::ExecutorThread()’: /ros2-dev/gazebo/.gazebo/plugins/velodyne/velodyne_plugin.cc:128:32: error: no matching function for call to ‘rclcpp::Node::create_subscription<std_msgs::msg::Float32>(std::__cxx11::basic_string<char>, rclcpp::QoS, boost::_bi::bind_t<void, boost::_mfi::mf1<void, gazebo::VelodynePlugin, std::shared_ptr<std_msgs::msg::Float32_<std::allocator<void>
> > >, boost::_bi::list2<boost::_bi::value<gazebo::VelodynePlugin*>, boost::arg<1> > >, rclcpp::SubscriptionOptions&)’
this->rosSubOptions);
^ In file included from /opt/ros/eloquent/include/rclcpp/executors/single_threaded_executor.hpp:28:0,
from /opt/ros/eloquent/include/rclcpp/executors.hpp:22,
from /opt/ros/eloquent/include/rclcpp/rclcpp.hpp:145,
from /ros2-dev/gazebo/.gazebo/plugins/velodyne/velodyne_plugin.cc:8: /opt/ros/eloquent/include/rclcpp/node.hpp:208:3: note: candidate: template<class MessageT, class CallbackT, class AllocatorT, class CallbackMessageT, class SubscriptionT, class MessageMemoryStrategyT> std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>&, typename MessageMemoryStrategyT::SharedPtr) create_subscription( ^~~~~~~~~~~~~~~~~~~ /opt/ros/eloquent/include/rclcpp/node.hpp:208:3: note: substitution of deduced template arguments resulted in errors seen above make[2]: *** [CMakeFiles/velodyne_plugin.dir/velodyne_plugin.cc.o] Error 1 make[1]: *** [CMakeFiles/velodyne_plugin.dir/all] Error 2 make: *** [all] Error 2
Edit: I tried std::bind instead of boost::bind. The following is the beginning of the very long error message:
In file included from /opt/ros/eloquent/include/rclcpp/subscriptionbase.hpp:26:0,
from /opt/ros/eloquent/include/rclcpp/callbackgroup.hpp:26,
from /opt/ros/eloquent/include/rclcpp/anyexecutable.hpp:20,
from /opt/ros/eloquent/include/rclcpp/memorystrategy.hpp:24,
from /opt/ros/eloquent/include/rclcpp/memorystrategies.hpp:18,
from /opt/ros/eloquent/include/rclcpp/executor.hpp:33,
from /opt/ros/eloquent/include/rclcpp/executors/multithreadedexecutor.hpp:25,
from /opt/ros/eloquent/include/rclcpp/executors.hpp:21,
from /opt/ros/eloquent/include/rclcpp/rclcpp.hpp:145,
from /ros2-dev/gazebo/.gazebo/plugins/velodyne/velodyneplugin.cc:9:
/opt/ros/eloquent/include/rclcpp/anysubscriptioncallback.hpp: In instantiation of ‘void rclcpp::AnySubscriptionCallback::set(CallbackT) [with CallbackT = std::Bind))(std::shared ptr > >)>; typename std::enableif<rclcpp::functiontraits::samearguments<CallbackT, std::function<void(std::sharedptr<Tp>)> >::value>::type* = 0; MessageT = std msgs::msg::Float32std::allocator<void >; Alloc = std::allocator]’:
/opt/ros/eloquent/include/rclcpp/subscription factory.hpp:87:3: required from ‘rclcpp::SubscriptionFactory rclcpp::createsubscriptionfactory(CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = stdmsgs::msg::Float32std::allocator<void >; CallbackT = std::Bind))(std::shared ptr > >)>; AllocatorT = std::allocator; CallbackMessageT = stdmsgs::msg::Float32std::allocator<void >; SubscriptionT = rclcpp::Subscription > >; MessageMemoryStrategyT = rclcpp::messagememorystrategy::MessageMemoryStrategy >, std::allocator >; typename MessageMemoryStrategyT::SharedPtr = std::sharedptr<rclcpp::messagememorystrategy::MessageMemoryStrategy<stdmsgs::msg::Float32std::allocator<void >, std::allocator > >]’
/opt/ros/eloquent/include/rclcpp/create subscription.hpp:67:63: required from ‘std::sharedptr rclcpp::create subscription(NodeT&&, const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = stdmsgs::msg::Float32std::allocator<void >; CallbackT = std::Bind))(std::shared ptr > >)>; AllocatorT = std::allocator; CallbackMessageT = stdmsgs::msg::Float32std::allocator<void >; SubscriptionT = rclcpp::Subscription > >; MessageMemoryStrategyT = rclcpp::messagememorystrategy::MessageMemoryStrategy >, std::allocator >; NodeT = rclcpp::Node&; std::cxx11::string = std::cxx11::basicstring; typename MessageMemoryStrategyT::SharedPtr = std::shared ptrrclcpp::message_memory_strategy::MessageMemoryStrategy<std_msgs::msg::Float32_<std::allocator<void >, std::allocator > >]’
/opt/ros/eloquent/include/rclcpp/nodeimpl.hpp:96:47: required from ‘std::sharedptr rclcpp::Node::createsubscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = std msgs::msg::Float32std::allocator<void >; CallbackT = std::Bind))(std::sharedptr<stdmsgs::msg::Float32std::allocator<void > >)>; AllocatorT = std::allocator; CallbackMessageT = std msgs::msg::Float32std::allocator<void >; SubscriptionT = rclcpp::Subscription<stdmsgs::msg::Float32std::allocator<void > >; MessageMemoryStrategyT = rclcpp::messagememorystrategy::MessageMemoryStrategy<stdmsgs::msg::Float32std::allocator<void >, std::allocator >; std:: cxx11::string = std::cxx11::basicstring; typename MessageMemoryStrategyT::SharedPtr = std::sharedptr<rclcpp::messagememorystrategy::MessageMemoryStrategy<stdmsgs::msg::Float32std::allocator<void >, std::allocator > >]’
/ros2-dev/gazebo/.gazebo/plugins/velodyne/velodyne plugin.cc:130:32: required from here
/opt/ros/eloquent/include/rclcpp/anysubscriptioncallback.hpp:84:26: error: no match for ‘operator=’ (operand types are ‘rclcpp::AnySubscriptionCallback >, std::allocator >::SharedPtrCallback {aka std::function > >)>}’ and ‘std::Bind))(std::shared ptr > >)>’)
sharedptrcallback_ = callback;
Asked by errcsool on 2020-01-27 02:04:15 UTC
Answers
Can you try std::bind
instead of boost::bind
?
Also, check that the signature of OnRosMsg
matches what's expected. Something like void OnRosMsg(const std_msgs::msg::Float32::SharedPtr _msg)
.
Asked by chapulina on 2020-01-27 13:22:03 UTC
Comments
OnRosMsg definition:
OnRosMsg(const std_msgs::msg::Float32::SharedPtr msg){
this->SetVelocity(msg->data);
}
Asked by errcsool on 2020-01-27 14:00:45 UTC
Using std::bind (very long error message), see edit
Asked by errcsool on 2020-01-27 14:04:20 UTC
Comments