
Hello guys,
I am trying to make a class with actionlib in ROS2 crystal. I started by modifying the example code here.
However, I get stuck in calling the function rclcpp_action::create_server. Is there any example for write a actionlib sever in class with ROS2 crystal??? Thank you!!!
here is the error I get
/home/q600/rclcpp_ws/src/universal_actionlib/src/universal_actionlib_server.cpp: In member function ‘void UniversalActionlibServer::init()’: /home/q600/rclcpp_ws/src/universal_actionlib/src/universal_actionlib_server.cpp:19:5: error: no matching function for call to ‘create_server<StringTask>(rclcpp::Node::SharedPtr&, std::__cxx11::string&, std::_Bind_helper<false, rclcpp_action::GoalResponse (UniversalActionlibServer::*)(std::array<unsigned char, 16>&, std::shared_ptr<universal_actionlib_interface::action::StringTask_Goal_Request_<std::allocator<void> > >), UniversalActionlibServer*, const std::_Placeholder<1>&, const std::_Placeholder<2>&>::type, std::_Bind_helper<false, rclcpp_action::CancelResponse (UniversalActionlibServer::*)(std::shared_ptr<rclcpp_action::ServerGoalHandle<universal_actionlib_interface::action::StringTask> >), UniversalActionlibServer*, const std::_Placeholder<1>&>::type, std::_Bind_helper<false, void (UniversalActionlibServer::*)(std::shared_ptr<rclcpp_action::ServerGoalHandle<universal_actionlib_interface::action::StringTask> >), UniversalActionlibServer*, const std::_Placeholder<1>&>::type)’ ); ^ In file included from /opt/ros/crystal/include/rclcpp_action/rclcpp_action.hpp:34:0, from /home/q600/rclcpp_ws/src/universal_actionlib/include/universal_actionlib/universal_actionlib_server.hpp:4, from /home/q600/rclcpp_ws/src/universal_actionlib/src/universal_actionlib_server.cpp:1: /opt/ros/crystal/include/rclcpp_action/create_server.hpp:36:1: note: candidate: template<class ActionT> typename rclcpp_action::Server<ActionT>::SharedPtr rclcpp_action::create_server(rclcpp::Node::SharedPtr, const string&, typename rclcpp_action::Server<ActionT>::GoalCallback, typename rclcpp_action::Server<ActionT>::CancelCallback, typename rclcpp_action::Server<ActionT>::AcceptedCallback, const rcl_action_server_options_t&, rclcpp::callback_group::CallbackGroup::SharedPtr) create_server( ^~~~~~~~~~~~~ I also check the code here. But I still didn't get it how to use actionlib in class.
Here is my code:
StringTask.action
# Goal string task_s --- # Result string result_s --- # Feedback string feedback_s actionlib_server_class.hpp
#ifndef UNIVERSAL_ACTIONLIB_SERVER_H #define UNIVERSAL_ACTIONLIB_SERVER_H #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "universal_actionlib_interface/action/string_task.hpp" #include "string" #include "iostream" #include "thread" #include "functional" using namespace std; using StringTask = universal_actionlib_interface::action::StringTask; using GoalHandleStringTask = rclcpp_action::ServerGoalHandle<StringTask>; using GoalID = rclcpp_action::GoalID; class UniversalActionlibServer { public: UniversalActionlibServer(string action_name); ~UniversalActionlibServer(){}; void init(); private: rclcpp_action::GoalResponse handle_goal(GoalID &uuid, shared_ptr<StringTask::Goal> goal); rclcpp_action::CancelResponse handle_cancel(shared_ptr<GoalHandleStringTask> goal_handle); void handle_accepted(shared_ptr<GoalHandleStringTask> goal_handle); void execute(const shared_ptr<GoalHandleStringTask> goal_handle); string action_name_; rclcpp::Node::SharedPtr node_; }; actionlib_server.cpp
#include "universal_actionlib/universal_actionlib_server.hpp" UniversalActionlibServer::UniversalActionlibServer(string action_name) { action_name_ = action_name; node_ = rclcpp::Node::make_shared(action_name_); RCLCPP_INFO(rclcpp::get_logger("server"),"Establishing the action server %s...",action_name_); } void UniversalActionlibServer::init() { auto action_server = rclcpp_action::create_server<StringTask>( node_, action_name_, std::bind(&UniversalActionlibServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2), std::bind(&UniversalActionlibServer::handle_cancel, this, std::placeholders::_1), std::bind(&UniversalActionlibServer::handle_accepted, this, std::placeholders::_1) ); } rclcpp_action::GoalResponse UniversalActionlibServer::handle_goal(GoalID &uuid, shared_ptr<StringTask::Goal> goal) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } rclcpp_action::CancelResponse UniversalActionlibServer::handle_cancel(shared_ptr<GoalHandleStringTask> goal_handle) { RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal"); (void)goal_handle; return rclcpp_action::CancelResponse::ACCEPT; } void UniversalActionlibServer::handle_accepted(shared_ptr<GoalHandleStringTask> goal_handle) { std::thread{&UniversalActionlibServer::execute, this, goal_handle}.detach(); } void UniversalActionlibServer::execute(const shared_ptr<GoalHandleStringTask> goal_handle) { RCLCPP_INFO(rclcpp::get_logger("server"), "Executing goal"); rclcpp::Rate loop_rate(1); const auto goal = goal_handle->get_goal(); auto _feedback = std::make_shared<StringTask::Feedback>(); auto _result = std::make_shared<StringTask::Result>(); // Storage the result from do_something string tmp_goal; string tmp_feedback; string tmp_result; tmp_goal = goal->task_s; while( do_something()) { _feedback->feedback_s = tmp_feedback; goal_handle->publish_feedback(_feedback); RCLCPP_INFO(rclcpp::get_logger("server"), "Publish Feedback"); loop_rate.sleep(); } _result->result_s = tmp_result; goal_handle->set_succeeded(_result); RCLCPP_INFO(rclcpp::get_logger("server"), "Goal Suceeded"); } #endif // UNIVERSAL_ACTIONLIB_SERVER_H Originally posted by PowerfulMing on ROS Answers with karma: 40 on 2019-02-18
Post score: 0