Skill look_at
Version: 1.0.0
Default path:
/skill/look_atDatatype: interaction_skills/action/LookAt
Definition source:
package.xmlin ros4hri/interaction_skills
Defines the gazing direction of the robot. This skill can be used to either look at a specific point in space (a ROS tf frame), or to set a generic gaze policy, such as looking at people around the robot.
Using the glance policy, you can also use this skill to brielfy look at
a specific point in space, before returning to the previous gaze policy.
Input parameters
policy
stringOne of the policies below, or empty string (in that case, the robot will look atpoint in space specified with the
targetparameter).Available policies:
random: randomly look around, with short fixationssocial: look around for faces, with fixations on detected facesglance: glance at a specific point in space, then return to the previous gaze policy.targetmust be specified.auto: automatic gaze policy, implementation-dependent. On PAL interactive robots, equivalent tosocial.reset: reset the gaze of the robot to looking straight.
target
geometry_msgs/msg/PointStampedtf frame to track. Ignored if the
policyparameter is set to one of the predefined policies.
Quick snippets
Call the skill from the command-line
$ ros2 action send_goal /skill/look_at interaction_skills/action/LookAt # 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 interaction_skills.action import
class LookatActionClient(Node):
def __init__(self):
super().__init__('look_at_client')
self._action_client = ActionClient(self, , '/skill/look_at')
def send_goal(self, a, b):
goal_msg = .Goal()
# TODO: adapt to the action's parameters
# check the LookAtGoal 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 "interaction_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 LookatActionClient : public rclcpp::Node
{
public:
using = interaction_skills::action::;
using GoalHandle = rclcpp_action::ClientGoalHandle<>;
explicit LookatActionClient(const rclcpp::NodeOptions & options)
: Node("look_at_action_client", options)
{
this->client_ptr_ = rclcpp_action::create_client<>(
this,
"");
this->timer_ = this->create_wall_timer(
500ms,
bind(&LookatActionClient::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 LookAtGoal 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(&LookatActionClient::goal_response_callback, this, _1);
send_goal_options.feedback_callback =
bind(&LookatActionClient::feedback_callback, this, _1, _2);
send_goal_options.result_callback =
bind(&LookatActionClient::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 LookatActionClient
RCLCPP_COMPONENTS_REGISTER_NODE(LookatActionClient)
You can call this skill from QML using the following code snippet. See ros_qml_plugin to learn more.
import Ros 2.0
// ...
LookAtSkill {
id: mySkill
onResult: {
console.log("Skill result: " + result);
}
onFeedback: {
console.log("Skill feedback: " + feedback);
}
}
// Call the skill
mySkill.look_at();
See also
List of other Interaction skills