Skip to content

Commit

Permalink
Merge pull request #90 from ibis-ssl/add-skills
Browse files Browse the repository at this point in the history
スキルシステムのアップデート
  • Loading branch information
HansRobo authored Feb 1, 2024
2 parents b9eb619 + b31d801 commit 6353f99
Show file tree
Hide file tree
Showing 19 changed files with 953 additions and 293 deletions.
4 changes: 3 additions & 1 deletion crane_robot_skills/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,9 @@ find_package(rclcpp_components REQUIRED)
ament_auto_find_build_dependencies()

ament_auto_add_library(${PROJECT_NAME}_component SHARED
src/robot_skills.cpp)
src/robot_skills.cpp
src/robot_command_as_skill.cpp
)

#rclcpp_components_register_nodes(${PROJECT_NAME}_component "crane::WorldModelPublisherComponent")

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,10 @@ class GetBallContact : public SkillBase<>
{
public:
explicit GetBallContact(uint8_t id, std::shared_ptr<WorldModelWrapper> & world_model)
: SkillBase<>("get_ball_contact", id, world_model, DefaultStates::DEFAULT)
: SkillBase<>("GetBallContact", id, world_model, DefaultStates::DEFAULT)
{
setParameter("min_contact_duration", 0.5);
setParameter("dribble_power", 0.5);
addStateFunction(
DefaultStates::DEFAULT,
[this](
Expand All @@ -30,9 +32,10 @@ class GetBallContact : public SkillBase<>
robot->ball_contact.getContactDuration())
.count()
<< std::endl;
// TODO: ロボットからのフィードバック情報を使う
if (
robot->ball_contact.getContactDuration() >
std::chrono::duration<double>(MINIMUM_CONTACT_DURATION)) {
std::chrono::duration<double>(getParameter<double>("min_contact_duration"))) {
return SkillBase::Status::SUCCESS;
} else {
double distance = (robot->pose.pos - world_model->ball.pos).norm();
Expand All @@ -42,7 +45,7 @@ class GetBallContact : public SkillBase<>
auto approach_vec = getApproachNormVec();
command.setDribblerTargetPosition(world_model->ball.pos);
command.setTargetTheta(getAngle(world_model->ball.pos - robot->pose.pos));
command.dribble(0.5);
command.dribble(getParameter<double>("dribble_power"));
return SkillBase::Status::RUNNING;
}
});
Expand Down Expand Up @@ -81,8 +84,6 @@ class GetBallContact : public SkillBase<>
Point last_contact_point;

// double target_distance = 0.0;

constexpr static double MINIMUM_CONTACT_DURATION = 0.5;
};
} // namespace crane
#endif // CRANE_ROBOT_SKILLS__GET_BALL_CONTACT_HPP_
9 changes: 7 additions & 2 deletions crane_robot_skills/include/crane_robot_skills/idle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,16 +16,21 @@ class Idle : public SkillBase<>
{
public:
explicit Idle(uint8_t id, std::shared_ptr<WorldModelWrapper> & world_model)
: SkillBase<>("idle", id, world_model, DefaultStates::DEFAULT)
: SkillBase<>("Idle", id, world_model, DefaultStates::DEFAULT)
{
setParameter("stop_by_position", true);
addStateFunction(
DefaultStates::DEFAULT,
[this](
const std::shared_ptr<WorldModelWrapper> & world_model,
const std::shared_ptr<RobotInfo> & robot,
crane::RobotCommandWrapper & command) -> SkillBase::Status {
// TODO: モーターをOFFにするようにしたほうがバッテリーに優しいかも
command.setVelocity(0., 0.);
if (getParameter<bool>("stop_by_position")) {
command.stopHere();
} else {
command.setVelocity(0., 0.);
}
return SkillBase::Status::RUNNING;
});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,17 +17,17 @@ class MoveToGeometry : public SkillBase<>
{
public:
explicit MoveToGeometry(
uint8_t id, Geometry geometry, std::shared_ptr<WorldModelWrapper> & world_model,
const double threshold = 0.1)
: SkillBase<>("move_to_geometry", id, world_model, DefaultStates::DEFAULT), geometry(geometry)
uint8_t id, Geometry geometry, std::shared_ptr<WorldModelWrapper> & world_model)
: SkillBase<>("MoveToGeometry", id, world_model, DefaultStates::DEFAULT), geometry(geometry)
{
setParameter("reach_threshold", 0.1);
addStateFunction(
DefaultStates::DEFAULT,
[this, threshold](
[this](
const std::shared_ptr<WorldModelWrapper> & world_model,
const std::shared_ptr<RobotInfo> & robot,
crane::RobotCommandWrapper & command) -> SkillBase::Status {
if ((robot->pose.pos - getTargetPoint()).norm() < threshold) {
if ((robot->pose.pos - getTargetPoint()).norm() < getParameter<double>("reach_threshold")) {
return SkillBase::Status::SUCCESS;
} else {
command.setTargetPosition(getTargetPoint());
Expand Down
56 changes: 41 additions & 15 deletions crane_robot_skills/include/crane_robot_skills/move_with_ball.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,46 +19,67 @@ namespace crane
class MoveWithBall : public SkillBase<>
{
public:
explicit MoveWithBall(Pose2D pose, uint8_t id, std::shared_ptr<WorldModelWrapper> & world_model)
: SkillBase<>("move_with_ball", id, world_model, DefaultStates::DEFAULT), target_pose(pose)
explicit MoveWithBall(uint8_t id, std::shared_ptr<WorldModelWrapper> & world_model)
: SkillBase<>("MoveWithBall", id, world_model, DefaultStates::DEFAULT)
{
setParameter("target_x", 0.0);
setParameter("target_y", 0.0);
setParameter("target_theta", 0.0);
setParameter("reach_threshold", 0.1);
setParameter("reach_angle_threshold", 0.1);
setParameter("ball_lost_timeout", 2.0);
setParameter("dribble_power", 0.1);
// これ以上の角度をずれて進むと停止する
setParameter("moving_direction_tolerance", 0.3);
// この時間以上ボールが離れたら停止する
setParameter("max_contact_lost_time", 0.3);
// ドリブル時の目標位置の設置距離
setParameter("dribble_target_horizon", 0.2);
addStateFunction(
DefaultStates::DEFAULT,
[this](
const std::shared_ptr<WorldModelWrapper> & world_model,
const std::shared_ptr<RobotInfo> & robot,
crane::RobotCommandWrapper & command) -> SkillBase::Status {
if (not robot->ball_contact.findPastContact(2.0)) {
Pose2D target_pose;
target_pose.pos.x() = getParameter<double>("target_x");
target_pose.pos.y() = getParameter<double>("target_y");
target_pose.theta = getParameter<double>("target_theta");
if (not robot->ball_contact.findPastContact(getParameter<double>("ball_lost_timeout"))) {
// ボールが離れたら失敗
return SkillBase::Status::FAILURE;
} else if (
(robot->pose.pos - target_pose.pos).norm() < 0.1 &&
std::abs(getAngleDiff(robot->pose.theta, target_pose.theta)) < 0.1) {
(robot->pose.pos - target_pose.pos).norm() < getParameter<double>("reach_threshold") &&
std::abs(getAngleDiff(robot->pose.theta, target_pose.theta)) <
getParameter<double>("reach_angle_threshold")) {
command.setTargetPosition(target_pose.pos, target_pose.theta);
command.dribble(0.2);
command.dribble(0.0);
// ターゲットに到着したら成功
return SkillBase::Status::SUCCESS;
} else {
command.setTargetPosition(getTargetPoint());
command.setTargetTheta(getTargetAngle());
command.dribble(0.1);
command.setTargetPosition(getTargetPoint(target_pose));
command.setTargetTheta(getTargetAngle(target_pose));
command.dribble(getParameter<double>("dribble_power"));
return SkillBase::Status::RUNNING;
}
});
}

Point getTargetPoint()
Point getTargetPoint(const Pose2D & target_pose)
{
// 正しい方向でドリブルできている場合だけ前進
if (getAngleDiff(robot->pose.theta, getTargetAngle()) < 0.3) {
if (robot->ball_contact.findPastContact(0.5)) {
return robot->pose.pos + (target_pose.pos - robot->pose.pos).normalized() * 0.2;
if (
getAngleDiff(robot->pose.theta, getTargetAngle(target_pose)) <
getParameter<double>("moving_direction_tolerance")) {
if (robot->ball_contact.findPastContact(getParameter<double>("max_contact_lost_time"))) {
return robot->pose.pos + (target_pose.pos - robot->pose.pos).normalized() *
getParameter<double>("dribble_target_horizon");
}
}
return robot->pose.pos;
}

double getTargetAngle()
double getTargetAngle(const Pose2D & target_pose)
{
auto distance = world_model->getDistanceFromRobot(robot->getID(), target_pose.pos);
auto to_target = getAngle(target_pose.pos - robot->pose.pos);
Expand All @@ -73,7 +94,12 @@ class MoveWithBall : public SkillBase<>
}
}

Pose2D target_pose;
void setTargetPose(const Pose2D & target_pose)
{
setParameter("target_x", target_pose.pos.x());
setParameter("target_y", target_pose.pos.y());
setParameter("target_theta", target_pose.theta);
}
};
} // namespace crane
#endif // CRANE_ROBOT_SKILLS__MOVE_WITH_BALL_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
// Copyright (c) 2023 ibis-ssl
//
// Use of this source code is governed by an MIT-style
// license that can be found in the LICENSE file or at
// https://opensource.org/licenses/MIT.

#ifndef CRANE_ROBOT_SKILLS__ROBOT_COMMAND_AS_SKILL_HPP_
#define CRANE_ROBOT_SKILLS__ROBOT_COMMAND_AS_SKILL_HPP_

#include <crane_geometry/eigen_adapter.hpp>
#include <crane_robot_skills/skill_base.hpp>

namespace crane
{

#define DEFINE_SKILL_COMMAND(name) \
class Cmd##name : public SkillBase<> \
{ \
public: \
explicit Cmd##name(uint8_t id, std::shared_ptr<WorldModelWrapper> & world_model); \
}

DEFINE_SKILL_COMMAND(KickWithChip);
DEFINE_SKILL_COMMAND(KickStraight);
DEFINE_SKILL_COMMAND(Dribble);
DEFINE_SKILL_COMMAND(SetVelocity);
DEFINE_SKILL_COMMAND(SetTargetPosition);
DEFINE_SKILL_COMMAND(SetDribblerTargetPosition);
DEFINE_SKILL_COMMAND(SetTargetTheta);
DEFINE_SKILL_COMMAND(StopHere);
DEFINE_SKILL_COMMAND(DisablePlacementAvoidance);
DEFINE_SKILL_COMMAND(EnablePlacementAvoidance);
DEFINE_SKILL_COMMAND(DisableBallAvoidance);
DEFINE_SKILL_COMMAND(EnableBallAvoidance);
DEFINE_SKILL_COMMAND(DisableCollisionAvoidance);
DEFINE_SKILL_COMMAND(EnableCollisionAvoidance);
DEFINE_SKILL_COMMAND(DisableGoalAreaAvoidance);
DEFINE_SKILL_COMMAND(EnableGoalAreaAvoidance);
DEFINE_SKILL_COMMAND(SetGoalieDefault);
DEFINE_SKILL_COMMAND(EnableBallCenteringControl);
DEFINE_SKILL_COMMAND(EnableLocalGoalie);
DEFINE_SKILL_COMMAND(SetMaxVelocity);
DEFINE_SKILL_COMMAND(SetMaxAcceleration);
DEFINE_SKILL_COMMAND(SetMaxOmega);
DEFINE_SKILL_COMMAND(SetTerminalVelocity);
DEFINE_SKILL_COMMAND(LookAt);
DEFINE_SKILL_COMMAND(LookAtBall);
DEFINE_SKILL_COMMAND(LookAtBallFrom);

} // namespace crane
#endif // CRANE_ROBOT_SKILLS__ROBOT_COMMAND_AS_SKILL_HPP_
48 changes: 47 additions & 1 deletion crane_robot_skills/include/crane_robot_skills/skill_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,14 @@

#undef DEFAULT

template <class... Ts>
struct overloaded : Ts...
{
using Ts::operator()...;
};
template <class... Ts>
overloaded(Ts...) -> overloaded<Ts...>;

namespace crane
{

Expand Down Expand Up @@ -66,6 +74,7 @@ template <typename StatesType = DefaultStates>
class SkillBase
{
public:
using ParameterType = std::variant<double, bool, int, std::string>;
enum class Status {
SUCCESS,
FAILURE,
Expand All @@ -91,8 +100,13 @@ class SkillBase

const std::string name;

Status run(RobotCommandWrapper & command)
Status run(
RobotCommandWrapper & command,
std::optional<std::unordered_map<std::string, ParameterType>> parameters_opt = std::nullopt)
{
if (parameters_opt) {
parameters = parameters_opt.value();
}
state_machine.update();
return state_functions[state_machine.getCurrentState()](world_model, robot, command);
}
Expand All @@ -116,6 +130,36 @@ class SkillBase
}
}

void getParameterSchemaString(std::ostream & os)
{
for (const auto & element : parameters) {
os << element.first << ": ";
std::visit(
overloaded{
[&](double e) { os << "double, " << e << std::endl; },
[&](int e) { os << "int, " << e << std::endl; },
[&](const std::string & e) { os << "string, " << e << std::endl; },
[&](bool e) { os << "bool, " << e << std::endl; }},
element.second);
}
}

void setParameter(const std::string & key, bool value) { parameters[key] = value; }

void setParameter(const std::string & key, int value) { parameters[key] = value; }

void setParameter(const std::string & key, double value) { parameters[key] = value; }

void setParameter(const std::string & key, const std::string & value) { parameters[key] = value; }

template <class T>
auto getParameter(const std::string & key)
{
return std::get<T>(parameters[key]);
}

const auto & getParameters() const { return parameters; }

protected:
// Status status = Status::RUNNING;

Expand All @@ -126,6 +170,8 @@ class SkillBase
StateMachine<StatesType> state_machine;

std::unordered_map<StatesType, StateFunctionType> state_functions;

std::unordered_map<std::string, ParameterType> parameters;
};
} // namespace crane
#endif // CRANE_ROBOT_SKILLS__SKILL_BASE_HPP_
18 changes: 18 additions & 0 deletions crane_robot_skills/include/crane_robot_skills/skills.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
// Copyright (c) 2024 ibis-ssl
//
// Use of this source code is governed by an MIT-style
// license that can be found in the LICENSE file or at
// https://opensource.org/licenses/MIT.

#ifndef CRANE_ROBOT_SKILLS__SKILLS_HPP_
#define CRANE_ROBOT_SKILLS__SKILLS_HPP_

#include <crane_robot_skills/get_ball_contact.hpp>
#include <crane_robot_skills/idle.hpp>
#include <crane_robot_skills/move_to_geometry.hpp>
#include <crane_robot_skills/move_with_ball.hpp>
#include <crane_robot_skills/robot_command_as_skill.hpp>
#include <crane_robot_skills/sleep.hpp>
#include <crane_robot_skills/turn_around_point.hpp>

#endif //CRANE_ROBOT_SKILLS__SKILLS_HPP_
46 changes: 46 additions & 0 deletions crane_robot_skills/include/crane_robot_skills/sleep.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// Copyright (c) 2024 ibis-ssl
//
// Use of this source code is governed by an MIT-style
// license that can be found in the LICENSE file or at
// https://opensource.org/licenses/MIT.

#ifndef CRANE_ROBOT_SKILLS__SLEEP_HPP_
#define CRANE_ROBOT_SKILLS__SLEEP_HPP_

#include <crane_geometry/eigen_adapter.hpp>
#include <crane_robot_skills/skill_base.hpp>

namespace crane
{
class Sleep : public SkillBase<>
{
public:
explicit Sleep(uint8_t id, std::shared_ptr<WorldModelWrapper> & world_model)
: SkillBase<>("Sleep", id, world_model, DefaultStates::DEFAULT)
{
setParameter("duration", 0.0);
addStateFunction(
DefaultStates::DEFAULT,
[this](
const std::shared_ptr<WorldModelWrapper> & world_model,
const std::shared_ptr<RobotInfo> & robot,
crane::RobotCommandWrapper & command) -> SkillBase::Status {
if (not is_started) {
start_time = std::chrono::steady_clock::now();
is_started = true;
}

auto elapsed_time =
std::chrono::duration<double>(std::chrono::steady_clock::now() - start_time);
if (elapsed_time.count() > getParameter<double>("duration")) {
return SkillBase::Status::SUCCESS;
} else {
return SkillBase::Status::RUNNING;
}
});
}
bool is_started = false;
std::chrono::time_point<std::chrono::steady_clock> start_time;
};
} // namespace crane
#endif // CRANE_ROBOT_SKILLS__SLEEP_HPP_
Loading

0 comments on commit 6353f99

Please sign in to comment.