Skill execute_cartesian_trajectory
Version: 1.0.0
Default path:
/skill/execute_cartesian_trajectoryDatatype: motion_skills_action_ExecuteCartesianTrajectory.action
Definition source:
package.xmlin ros4hri/motions_skills
Execute a trajectory on the robot by specifying a list of 3D points (and optionally, 3D orientations) to follow, with corresponding target timestamps.
If a specific skill implementation uses a 3D motion planner, tHe exact timestamps might vary based on the planner’s output.
By not providing timestamps, the skill implementation can decide on the timing based on its own constraints and capabilities.
Input parameters
trajectory
moveit_msgs/msg/CartesianTrajectory, requiredThe Cartesian trajectory to execute.
By setting the timestamps of each point to zero, the skill implementation is free to decide on the timing based on its own constraints and capabilities.
meta.priority
integer, default:128Between 0 and 255. Higher means this skill request will be prioritized.
Quick snippets
Call the skill from the command-line
$ ros2 action send_goal /skill/execute_cartesian_trajectory motion_skills/action/ExecuteCartesianTrajectory.action # then press Tab to complete the message prototype
Call the action from a Python script:
#!/usr/bin/env python
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from motion_skills.action import
class Executecartesiantrajectory.actionActionClient(Node):
def __init__(self):
super().__init__('execute_cartesian_trajectory_client')
self._action_client = ActionClient(self, , '/skill/execute_cartesian_trajectory')
def send_goal(self, a, b):
goal_msg = .Goal()
# TODO: adapt to the action's parameters
# check the ExecuteCartesianTrajectory.actionGoal message
# definition for the possible goal parameters
# goal_msg.a = a
# goal_msg.b = b
self._action_client.wait_for_server()
return self._action_client.send_goal_async(goal_msg)
if __name__ == '__main__':
rclpy.init(args=args)
action_client = ActionClient()
# TODO: adapt to your action's parameters
future = action_client.send_goal(a, b)
rclpy.spin_until_future_complete(action_client, future)
rclpy.shutdown()
Call the action from a C++ program:
#include <functional>
#include <future>
#include <memory>
#include <string>
#include <sstream>
#include <chrono>
#include "motion_skills/action/.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_hpp"
#include "rclcpp_components/register_node_macro.hpp"
using namespace std::chrono_literals;
using namespace std;
class Executecartesiantrajectory.actionActionClient : public rclcpp::Node
{
public:
using = motion_skills::action::;
using GoalHandle = rclcpp_action::ClientGoalHandle<>;
explicit Executecartesiantrajectory.actionActionClient(const rclcpp::NodeOptions & options)
: Node("execute_cartesian_trajectory_action_client", options)
{
this->client_ptr_ = rclcpp_action::create_client<>(
this,
"");
this->timer_ = this->create_wall_timer(
500ms,
bind(&Executecartesiantrajectory.actionActionClient::send_goal, this));
}
void send_goal()
{
using namespace std::placeholders;
this->timer_->cancel();
if (!this->client_ptr_->wait_for_action_server()) {
RCLCPP_ERROR(this->get_logger(), "Action server not available after waiting");
rclcpp::shutdown();
}
auto goal_msg = ::Goal();
// check the ExecuteCartesianTrajectory.actionGoal message
// definition for the possible goal parameters
// goal_msg.... = ...;
RCLCPP_INFO(this->get_logger(), "Sending goal");
auto send_goal_options = rclcpp_action::Client<>::SendGoalOptions();
send_goal_options.goal_response_callback =
bind(&Executecartesiantrajectory.actionActionClient::goal_response_callback, this, _1);
send_goal_options.feedback_callback =
bind(&Executecartesiantrajectory.actionActionClient::feedback_callback, this, _1, _2);
send_goal_options.result_callback =
bind(&Executecartesiantrajectory.actionActionClient::result_callback, this, _1);
this->client_ptr_->async_send_goal(goal_msg, send_goal_options);
}
private:
rclcpp_action::Client<>::SharedPtr client_ptr_;
rclcpp::TimerBase::SharedPtr timer_;
void goal_response_callback(const GoalHandle::SharedPtr & goal_handle)
{
if (!goal_handle) {
RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");
} else {
RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");
}
}
void feedback_callback(
GoalHandle::SharedPtr,
const shared_ptr<const ::Feedback> feedback)
{
stringstream ss;
ss << "Next number in sequence received: ";
for (auto number : feedback->partial_sequence) {
ss << number << " ";
}
RCLCPP_INFO(this->get_logger(), ss.str().c_str());
}
void result_callback(const GoalHandle::WrappedResult & result)
{
switch (result.code) {
case rclcpp_action::ResultCode::SUCCEEDED:
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
return;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
return;
default:
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
return;
}
stringstream ss;
ss << "Result received: ";
for (auto number : result.result->sequence) {
ss << number << " ";
}
RCLCPP_INFO(this->get_logger(), ss.str().c_str());
rclcpp::shutdown();
}
}; // class Executecartesiantrajectory.actionActionClient
RCLCPP_COMPONENTS_REGISTER_NODE(Executecartesiantrajectory.actionActionClient)
You can call this skill from QML using the following code snippet. See ros_qml_plugin to learn more.
import Ros 2.0
// ...
ExecuteCartesianTrajectorySkill {
id: mySkill
onResult: {
console.log("Skill result: " + result);
}
onFeedback: {
console.log("Skill feedback: " + feedback);
}
}
// Call the skill
mySkill.execute_cartesian_trajectory();
See also
List of other Motions skills