ROS2: Can subscribe to String, but not Twist, "no overloaded function"
Using the example subscriber found in the official ROS2 tutorials, I was able to create a subscriber that listened for String messages. I then tried to simply change it to listen to Twist messages, and I get a ton of errors, After doing some research, it appears to have something to do with the arguments in my callback function. I tried the solutions from these two sources, but nothing worked!
https://github.com/ros2/rclcpp/issues...
https://answers.ros.org/question/3083...
Ignoring the silly class name and motor controller stuff, here is my cpp src file:
#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
#include "ctre/Phoenix.h"
#include "ctre/phoenix/platform/Platform.h"
#include "ctre/phoenix/platform/can/PlatformCAN.h"
#include "ctre/phoenix/unmanaged/Unmanaged.h"
#include <string>
#include "rclcpp/node.hpp"
#include "ctre/phoenix/MotorControl/ControlMode.h"
using namespace std;
using namespace ctre::phoenix;
using namespace ctre::phoenix::platform;
using namespace ctre::phoenix::motorcontrol;
using namespace ctre::phoenix::motorcontrol::can;
using std::placeholders::_1;
class Hello : public rclcpp::Node
{
public:
Hello() : Node("pub_hello")
{
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscriber;
subscriber = this->create_subscription<geometry_msgs::msg::Twist>(
"topic", 10, std::bind(&Hello::topic_callback, this, _1));
RCLCPP_INFO(this->get_logger(), "Node Running");
}
void topic_callback(const geometry_msgs::msg::Twist) const
{
RCLCPP_INFO(this->get_logger(), "I heard");
}
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
TalonSRX talon = 1;
auto node = std::make_shared<Hello>();
ctre::phoenix::platform::can::SetCANInterface("can0");
talon.Set(ControlMode::Velocity, 0);
while(rclcpp::ok())
{
rclcpp::spin(node);
}
rclcpp::shutdown();
return 0;
}
And the large amount of errors that follow:
hello.cpp
C:\dev\ros2_foxy\include\rclcpp/subscription_factory.hpp(97): error C2672: 'rclcpp::AnySubscriptionCallback<CallbackMessageT,AllocatorT>::set': no matching overloaded function found [C:\dev\colcon_ws\build\lunabotics2021\hello.vcxproj]
with
[
CallbackMessageT=geometry_msgs::msg::Twist,
AllocatorT=std::allocator<void>
]
C:\dev\ros2_foxy\include\rclcpp/create_subscription.hpp(143): note: see reference to function template instantiation 'rclcpp::SubscriptionFactory rclcpp::create_subscription_factory<MessageT,_Ty,std::allocator<void>,CallbackMessageT,rclcpp::Subscription<CallbackMessageT,std::allocator<void>,rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT,AllocatorT>>,rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT,AllocatorT>>(CallbackT &&,const rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void>> &,std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT,AllocatorT>>,std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>>)' being compiled
with
[
MessageT=geometry_msgs::msg::Twist,
_Ty=std::_Binder<std::_Unforced,void (__cdecl Hello::* )(geometry_msgs::msg::Twist) const,Hello *,const std::_Ph<1> &>,
CallbackMessageT=geometry_msgs::msg::Twist,
AllocatorT=std::allocator<void>,
CallbackT=std::_Binder<std::_Unforced,void (__cdecl Hello::* )(geometry_msgs::msg::Twist) const,Hello *,const std::_Ph<1> &>
]
c:\dev\ros2_foxy\include\rclcpp\node_impl.hpp(104): note: see reference to function template instantiation 'std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::Twist,std::allocator<void>,rclcpp::message_memory_strategy::MessageMemoryStrategy<CallbackMessageT,AllocatorT>>> rclcpp::create_subscription<MessageT,_Ty,std::allocator<void>,geometry_msgs::msg::Twist_<std::allocator<void>>,rclcpp::Subscription<CallbackMessageT,AllocatorT,rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT,AllocatorT>>,rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT,AllocatorT>,rclcpp::Node&>(NodeT,const std::string &,const rclcpp::QoS &,CallbackT &&,const rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void>> &,std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT,AllocatorT>>)' being compiled
with
[
CallbackMessageT=geometry_msgs::msg::Twist,
AllocatorT=std::allocator<void>,
MessageT=geometry_msgs::msg::Twist,
_Ty=std::_Binder<std::_Unforced,void (__cdecl Hello::* )(geometry_msgs::msg::Twist) const,Hello *,const std::_Ph<1> &>,
NodeT=rclcpp::Node &,
CallbackT=std::_Binder<std::_Unforced,void (__cdecl Hello::* )(geometry_msgs ...