10.30

LGQLHT發表於2024-10-30
actionlib_server_node.cpp
actionlib_client_node.cpp
ActionlibExMsg.action
#goal definition
int32 whole_distance
---
#result definition
bool is_finish
---
#feedback
int32 moving_meter
  <build_depend>message_generation</build_depend>
  <exec_depend>message_runtime</exec_depend>
  add_action_files(
    FILES
    ActionlibExMsg.action
    
  )
  generate_messages(
    DEPENDENCIES
    actionlib_msgs
  )
add_executable(actionlib_client_node src/actionlib_client_node.cpp)
add_dependencies(actionlib_client_node ${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS})
target_link_libraries(actionlib_client_node ${catkin_LIBRARIES})
add_executable(actionlib_server_node src/actionlib_server_node.cpp)
add_dependencies(actionlib_server_node ${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS})
target_link_libraries(actionlib_server_node ${catkin_LIBRARIES})

---------

#include <actionlib/client/simple_action_client.h>
#include <actionlib_example_pkg/ActionlibExMsgAction.h>

// Action完成後呼叫的回撥函式
void doneCb(const actionlib::SimpleClientGoalState& state,
            const actionlib_example_pkg::ActionlibExMsgResultConstPtr& result)
{
    ROS_INFO("Task completed!");
    ros::shutdown();
}

// Action啟用時呼叫的回撥函式
void activeCb()
{
    ROS_INFO("Goal is active! The robot begins to move forward.");
}

// Action執行過程中接收反饋的回撥函式
void feedbackCb(const actionlib_example_pkg::ActionlibExMsgFeedbackConstPtr& feedback)
{
    ROS_INFO("The robot has moved forward %d meters.", feedback->moving_meter);
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "actionlib_client_node");

    // 建立一個action的client,指定action名稱為“moving_forward”
    actionlib::SimpleActionClient<actionlib_example_pkg::ActionlibExMsgAction> client("moving_forward", true);

    ROS_INFO("Waiting for action server to start");
    client.waitForServer(); // 等待伺服器響應
    ROS_INFO("Action server started");

    // 建立一個目標:移動機器人前進10m
    actionlib_example_pkg::ActionlibExMsgGoal goal;
    goal.whole_distance = 10;

    // 把action的任務目標傳送給伺服器,繫結上面定義的各種回撥函式
    client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);

    ros::spin();

    return 0;
}

-----------

#include <ros/ros.h>

#include <actionlib/server/simple_action_server.h>

#include <actionlib_example_pkg/ActionlibExMsgAction.h>

// 伺服器接收任務目標後,呼叫該函式執行任務
void execute(const actionlib_example_pkg::ActionlibExMsgGoalConstPtr& goal,
             actionlib::SimpleActionServer<actionlib_example_pkg::ActionlibExMsgAction>* as) {
    ros::Rate r(0.5);
    actionlib_example_pkg::ActionlibExMsgFeedback feedback;

    ROS_INFO("Task: The robot moves forward %d meters.", goal->whole_distance);

    for(int i = 1; i <= goal->whole_distance; ++i) {
        feedback.moving_meter = i;
        as->publishFeedback(feedback); // 反饋任務執行的過程
        r.sleep();
    }

    ROS_INFO("Task completed!");
    as->setSucceeded();
}

int main(int argc, char** argv) {
    ros::init(argc, argv, "actionlib_server_node");
    ros::NodeHandle n;

    // 建立一個action的server,指定action名稱為"moving_forward"
    actionlib::SimpleActionServer<actionlib_example_pkg::ActionlibExMsgAction> server(
        n, "moving_forward", boost::bind(&execute, _1, &server), false);

    // 伺服器啟動
    server.start();

    ros::spin();

    return 0;
}