This commit is contained in:
Bastian Hofmann 2023-06-17 15:51:48 +00:00
parent 97db29a669
commit a26d82f4fe
24 changed files with 136 additions and 70 deletions

View File

@ -1,4 +1,4 @@
#!/bin/bash #!/bin/bash
pushd "$(dirname "$0")" || exit pushd "$(dirname "$0")" || exit
colcon build --event-handlers console_cohesion+ --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -G Ninja colcon build --event-handlers console_cohesion+ --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -G Ninja
popd || exit popd || exit

@ -1 +0,0 @@
Subproject commit 55dd7680ff7234c825efa1dd0c104e5629448972

View File

@ -2,11 +2,10 @@
// Created by bastian on 28.02.22. // Created by bastian on 28.02.22.
// //
#include "Area.h" #include "Extensions.hpp"
#include <geometry_msgs/msg/pose.hpp>
namespace BT { namespace BT {
template<> template<> [[nodiscard]]
std::shared_ptr<Position2D> convertFromString(StringView str) { std::shared_ptr<Position2D> convertFromString(StringView str) {
auto split = splitString(str, ','); auto split = splitString(str, ',');
if (split.size() != 2) { if (split.size() != 2) {
@ -19,7 +18,7 @@ namespace BT {
return pos; return pos;
} }
template<> template<> [[nodiscard]]
std::shared_ptr<Area> convertFromString(StringView str) { std::shared_ptr<Area> convertFromString(StringView str) {
auto parts = splitString(str, '|'); auto parts = splitString(str, '|');
if (parts.size() < 3) { if (parts.size() < 3) {
@ -35,7 +34,7 @@ namespace BT {
return output; return output;
} }
template<> template<> [[nodiscard]]
std::shared_ptr<geometry_msgs::msg::Pose> convertFromString(StringView str) { std::shared_ptr<geometry_msgs::msg::Pose> convertFromString(StringView str) {
auto parts = splitString(str, ','); auto parts = splitString(str, ',');
if (!(parts.size() == 3 || parts.size() == 7)) { if (!(parts.size() == 3 || parts.size() == 7)) {
@ -61,7 +60,7 @@ namespace BT {
return pose; return pose;
} }
template<> template<> [[nodiscard]]
std::shared_ptr<geometry_msgs::msg::Point> convertFromString(StringView str) { std::shared_ptr<geometry_msgs::msg::Point> convertFromString(StringView str) {
auto parts = splitString(str, ','); auto parts = splitString(str, ',');
if (parts.size() != 3) { if (parts.size() != 3) {
@ -76,7 +75,7 @@ namespace BT {
return point; return point;
} }
template<> template<> [[nodiscard]]
std::shared_ptr<geometry_msgs::msg::Quaternion> convertFromString(StringView str) { std::shared_ptr<geometry_msgs::msg::Quaternion> convertFromString(StringView str) {
auto parts = splitString(str, ','); auto parts = splitString(str, ',');
if (parts.size() != 4) { if (parts.size() != 4) {

View File

@ -0,0 +1,27 @@
//
// Created by bastian on 28.02.22.
//
#ifndef BUILD_EXTENSIONS_H
#define BUILD_EXTENSIONS_H
#include "Area.h"
#include <geometry_msgs/msg/pose.hpp>
namespace BT {
template<> [[nodiscard]]
std::shared_ptr<Position2D> convertFromString(StringView str);
template<> [[nodiscard]]
std::shared_ptr<Area> convertFromString(StringView str);
template<> [[nodiscard]]
std::shared_ptr<geometry_msgs::msg::Pose> convertFromString(StringView str);
template<> [[nodiscard]]
std::shared_ptr<geometry_msgs::msg::Point> convertFromString(StringView str);
template<> [[nodiscard]]
std::shared_ptr<geometry_msgs::msg::Quaternion> convertFromString(StringView str);
}
#endif //BUILD_EXTENSIONS_H

View File

@ -1,7 +1,10 @@
#include "Extensions.hpp"
#include "Area.h" #include "Area.h"
#include <behaviortree_cpp_v3/basic_types.h> #include <behaviortree_cpp_v3/basic_types.h>
#include <behaviortree_cpp_v3/blackboard.h> #include <behaviortree_cpp_v3/blackboard.h>
#include <behaviortree_cpp_v3/bt_factory.h> #include <behaviortree_cpp_v3/bt_factory.h>
#include <boost/exception/exception.hpp>
#include <geometry_msgs/msg/detail/pose__struct.hpp>
#include <rclcpp/logging.hpp> #include <rclcpp/logging.hpp>
#include <rclcpp/rclcpp.hpp> #include <rclcpp/rclcpp.hpp>
#include <random> #include <random>
@ -20,10 +23,14 @@
#include <chrono> #include <chrono>
#include <thread> #include <thread>
using namespace BT;
int main(int argc, char **argv) { int main(int argc, char **argv) {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::NodeOptions node_options; rclcpp::NodeOptions node_options;
convertFromString<std::shared_ptr<geometry_msgs::msg::Pose>>("0,0,0");
auto mainNode = rclcpp::Node::make_shared("tree_general_node", node_options); auto mainNode = rclcpp::Node::make_shared("tree_general_node", node_options);
mainNode -> declare_parameter("trees",std::vector<std::string>({})); mainNode -> declare_parameter("trees",std::vector<std::string>({}));
@ -51,12 +58,12 @@ int main(int argc, char **argv) {
auto connection = std::make_shared<MoveConnection>(moveNode, "arm"); auto connection = std::make_shared<MoveConnection>(moveNode, "arm");
executor.add_node(moveNode); executor.add_node(moveNode);
factory.registerBuilder<RobotMove>("RobotMove", [&connection](const std::string &name, const NodeConfiguration &config) { factory.registerBuilder<RobotMove>("RobotMove", [connection](const std::string &name, const NodeConfiguration &config) {
return std::make_unique<RobotMove>(name, config, &connection); return std::make_unique<RobotMove>(name, config, connection);
}); });
factory.registerBuilder<SetRobotVelocity>("SetRobotVelocity", [&connection](const std::string &name, const NodeConfiguration &config) { factory.registerBuilder<SetRobotVelocity>("SetRobotVelocity", [connection](const std::string &name, const NodeConfiguration &config) {
return std::make_unique<SetRobotVelocity>(name, config, &connection); return std::make_unique<SetRobotVelocity>(name, config, connection);
}); });

View File

@ -18,7 +18,7 @@ BT::PortsList ActorAnimation::providedPorts() {
} }
BT::NodeStatus ActorAnimation::onStart() { BT::NodeStatus ActorAnimation::onStart() {
std::cout << "started animation" << std::endl; std::cout << "started actor animation" << std::endl;
ros_actor_action_server_msgs::action::Animation::Goal goal; ros_actor_action_server_msgs::action::Animation::Goal goal;
@ -37,8 +37,10 @@ BT::NodeStatus ActorAnimation::onStart() {
send_goal_options.result_callback = [=](const ClientGoalHandle<Animation>::WrappedResult & parameter) { send_goal_options.result_callback = [=](const ClientGoalHandle<Animation>::WrappedResult & parameter) {
mutex.lock(); mutex.lock();
if(parameter.code == ResultCode::SUCCEEDED){ if(parameter.code == ResultCode::SUCCEEDED){
std::cout << "finished actor animation" << std::endl;
result = BT::NodeStatus::SUCCESS; result = BT::NodeStatus::SUCCESS;
}else{ }else{
std::cout << "failed actor animation" << std::endl;
result = BT::NodeStatus::FAILURE; result = BT::NodeStatus::FAILURE;
} }
mutex.unlock(); mutex.unlock();
@ -53,14 +55,12 @@ BT::NodeStatus ActorAnimation::onStart() {
BT::NodeStatus ActorAnimation::onRunning() { BT::NodeStatus ActorAnimation::onRunning() {
mutex.lock(); mutex.lock();
auto status = result; auto status = result;
if(result != BT::NodeStatus::RUNNING){
result = BT::NodeStatus::IDLE;
}
mutex.unlock(); mutex.unlock();
return status; return status;
} }
void ActorAnimation::onHalted() { void ActorAnimation::onHalted() {
std::cout << "halted animation" << std::endl; std::cout << "halted actor animation" << std::endl;
client->async_cancel_all_goals(); client->async_cancel_all_goals();
result = BT::NodeStatus::FAILURE;
} }

View File

@ -2,6 +2,7 @@
// Created by bastian on 26.03.22. // Created by bastian on 26.03.22.
// //
#include "../Extensions.hpp"
#include "ActorMovement.h" #include "ActorMovement.h"
#include <action_msgs/msg/detail/goal_status__struct.hpp> #include <action_msgs/msg/detail/goal_status__struct.hpp>
#include <behaviortree_cpp_v3/basic_types.h> #include <behaviortree_cpp_v3/basic_types.h>
@ -22,7 +23,7 @@ BT::PortsList ActorMovement::providedPorts() {
} }
BT::NodeStatus ActorMovement::onStart() { BT::NodeStatus ActorMovement::onStart() {
std::cout << "started moving" << std::endl; std::cout << "started actor movement" << std::endl;
ros_actor_action_server_msgs::action::Movement::Goal goal; ros_actor_action_server_msgs::action::Movement::Goal goal;
@ -51,10 +52,10 @@ BT::NodeStatus ActorMovement::onStart() {
send_goal_options.result_callback = [&](ClientGoalHandle<Movement>::WrappedResult parameter) { send_goal_options.result_callback = [&](ClientGoalHandle<Movement>::WrappedResult parameter) {
mutex.lock(); mutex.lock();
if(parameter.code == ResultCode::SUCCEEDED){ if(parameter.code == ResultCode::SUCCEEDED){
std::cout << "Success?" << std::endl; std::cout << "finished actor movement" << std::endl;
result = BT::NodeStatus::SUCCESS; result = BT::NodeStatus::SUCCESS;
}else{ }else{
std::cout << "Failure?" << std::endl; std::cout << "failed actor movement" << std::endl;
result = BT::NodeStatus::FAILURE; result = BT::NodeStatus::FAILURE;
} }
mutex.unlock(); mutex.unlock();
@ -81,15 +82,12 @@ BT::NodeStatus ActorMovement::onStart() {
BT::NodeStatus ActorMovement::onRunning() { BT::NodeStatus ActorMovement::onRunning() {
mutex.lock(); mutex.lock();
auto status = result; auto status = result;
if(result != BT::NodeStatus::RUNNING){
result = BT::NodeStatus::IDLE;
}
mutex.unlock(); mutex.unlock();
return status; return status;
} }
void ActorMovement::onHalted() { void ActorMovement::onHalted() {
std::cout << "halted move" << std::endl; std::cout << "halted actor movement" << std::endl;
client->async_cancel_all_goals(); client->async_cancel_all_goals();
result = BT::NodeStatus::IDLE; result = BT::NodeStatus::FAILURE;
} }

View File

@ -83,7 +83,6 @@ BT::NodeStatus BT::GenerateXYPose::tick() {
randomPose->orientation.y = 0; randomPose->orientation.y = 0;
randomPose->orientation.z = 0; randomPose->orientation.z = 0;
printf("Generated Target: %f %f\n", pos.x, pos.y);
setOutput<std::shared_ptr<geometry_msgs::msg::Pose>>("pose", randomPose); setOutput<std::shared_ptr<geometry_msgs::msg::Pose>>("pose", randomPose);
return NodeStatus::SUCCESS; return NodeStatus::SUCCESS;
} }

View File

@ -18,7 +18,7 @@ BT::NodeStatus BT::InterruptableSequence::tick() {
setStatus(NodeStatus::RUNNING); setStatus(NodeStatus::RUNNING);
if(result==NodeStatus::FAILURE){ if(result==NodeStatus::FAILURE){
haltChildren(); resetChildren();
position=0; position=0;
return NodeStatus::FAILURE; return NodeStatus::FAILURE;
} }
@ -26,7 +26,7 @@ BT::NodeStatus BT::InterruptableSequence::tick() {
if(result==NodeStatus::SUCCESS){ if(result==NodeStatus::SUCCESS){
position++; position++;
if(position>=children_nodes_.size()){ if(position>=children_nodes_.size()){
haltChildren(); resetChildren();
position=0; position=0;
return NodeStatus::SUCCESS; return NodeStatus::SUCCESS;
} }

View File

@ -11,20 +11,19 @@ void MoveConnection::planAndExecute(const std::shared_ptr<geometry_msgs::msg::Po
std::cout<<"planAndExecute."<<std::endl; std::cout<<"planAndExecute."<<std::endl;
lock.lock(); lock.lock();
state = RUNNING; state = RUNNING;
std::cout<<"got lock."<<std::endl;
lastTarget = pose; lastTarget = pose;
lastCallback = callback; lastCallback = callback;
moveGroup.setMaxVelocityScalingFactor(currentSpeed); moveGroup.setMaxVelocityScalingFactor(currentSpeed);
moveGroup.setMaxAccelerationScalingFactor(1); moveGroup.setMaxAccelerationScalingFactor(1);
std::cout<<"Starting planning"<<std::endl;
std::thread([&](){
moveGroup.setPoseTarget(*lastTarget); moveGroup.setPoseTarget(*lastTarget);
moveGroup.setGoalJointTolerance(0.01); moveGroup.setGoalJointTolerance(0.01);
moveGroup.setGoalOrientationTolerance(0.01); moveGroup.setGoalOrientationTolerance(0.01);
std::cout<<"Starting planning"<<std::endl;
std::thread([&](){
std::cout<<"Parameters set."<<std::endl; std::cout<<"Parameters set."<<std::endl;
auto finished = moveGroup.move() == moveit::core::MoveItErrorCode::SUCCESS; auto finished = moveGroup.move() == moveit::core::MoveItErrorCode::SUCCESS;

View File

@ -12,7 +12,7 @@
class MoveConnection { class MoveConnection {
private: private:
enum {IDLE,RUNNING,SPEED_CHANGE} state; enum {IDLE,RUNNING,SPEED_CHANGE} state = IDLE;
moveit::planning_interface::MoveGroupInterface moveGroup; moveit::planning_interface::MoveGroupInterface moveGroup;
std::shared_ptr<geometry_msgs::msg::Pose> lastTarget = nullptr; std::shared_ptr<geometry_msgs::msg::Pose> lastTarget = nullptr;
std::function<void(bool)> lastCallback = [](__attribute__((unused))bool finished) {}; std::function<void(bool)> lastCallback = [](__attribute__((unused))bool finished) {};

View File

@ -5,7 +5,7 @@
#include "RobotMove.h" #include "RobotMove.h"
BT::RobotMove::RobotMove(const std::string &name, const BT::NodeConfiguration &config, BT::RobotMove::RobotMove(const std::string &name, const BT::NodeConfiguration &config,
std::shared_ptr<MoveConnection> *connection) std::shared_ptr<MoveConnection> connection)
: StatefulActionNode(name, config) { : StatefulActionNode(name, config) {
this->connection = connection; this->connection = connection;
} }
@ -20,7 +20,7 @@ BT::NodeStatus BT::RobotMove::onStart() {
printf("X:%f Y:%f Z:%f\n",pose->position.x,pose->position.y,pose->position.z); printf("X:%f Y:%f Z:%f\n",pose->position.x,pose->position.y,pose->position.z);
printf("W:%f X:%f Y:%f Z:%f\n",pose->orientation.w,pose->orientation.x,pose->orientation.y,pose->orientation.z); printf("W:%f X:%f Y:%f Z:%f\n",pose->orientation.w,pose->orientation.x,pose->orientation.y,pose->orientation.z);
asyncResult = NodeStatus::RUNNING; asyncResult = NodeStatus::RUNNING;
connection->get()->planAndExecute(pose,[this](bool finished){ connection->planAndExecute(pose,[this](bool finished){
if(finished){ if(finished){
printf("Finished move."); printf("Finished move.");
asyncResult = NodeStatus::SUCCESS; asyncResult = NodeStatus::SUCCESS;
@ -42,7 +42,7 @@ BT::NodeStatus BT::RobotMove::onRunning() {
void BT::RobotMove::onHalted() { void BT::RobotMove::onHalted() {
std::cout << "Halting RobotMove" << std::endl; std::cout << "Halting RobotMove" << std::endl;
connection->get()->stop(); connection->stop();
asyncResult=NodeStatus::FAILURE; asyncResult=NodeStatus::FAILURE;
} }

View File

@ -16,12 +16,12 @@ namespace BT {
class RobotMove : public StatefulActionNode { class RobotMove : public StatefulActionNode {
private: private:
std::shared_ptr<MoveConnection> *connection; std::shared_ptr<MoveConnection> connection;
NodeStatus asyncResult = NodeStatus::FAILURE; NodeStatus asyncResult = NodeStatus::FAILURE;
public: public:
RobotMove(const std::string &name, const BT::NodeConfiguration &config, RobotMove(const std::string &name, const BT::NodeConfiguration &config,
std::shared_ptr<MoveConnection> *connection); std::shared_ptr<MoveConnection> connection);
NodeStatus onStart() override; NodeStatus onStart() override;

View File

@ -11,7 +11,7 @@ BT::NodeStatus BT::SetRobotVelocity::tick() {
std::cout<<"No velocity given."<<std::endl; std::cout<<"No velocity given."<<std::endl;
return NodeStatus::FAILURE; return NodeStatus::FAILURE;
} }
connection->get()->setSpeedMultiplier(velocity); connection->setSpeedMultiplier(velocity);
return NodeStatus::SUCCESS; return NodeStatus::SUCCESS;
} }
@ -21,7 +21,7 @@ BT::PortsList BT::SetRobotVelocity::providedPorts() {
}; };
} }
BT::SetRobotVelocity::SetRobotVelocity(const std::string &name, const BT::NodeConfiguration &config, std::shared_ptr<MoveConnection> *connection) : SyncActionNode( BT::SetRobotVelocity::SetRobotVelocity(const std::string &name, const BT::NodeConfiguration &config, std::shared_ptr<MoveConnection> connection) : SyncActionNode(
name, config) { name, config) {
this->connection = connection; this->connection = connection;
} }

View File

@ -11,11 +11,11 @@
namespace BT { namespace BT {
class SetRobotVelocity: public SyncActionNode { class SetRobotVelocity: public SyncActionNode {
private: private:
std::shared_ptr<MoveConnection> *connection{}; std::shared_ptr<MoveConnection> connection;
public: public:
SetRobotVelocity(const std::string &name, const NodeConfiguration &config, SetRobotVelocity(const std::string &name, const NodeConfiguration &config,
std::shared_ptr<MoveConnection> *connection); std::shared_ptr<MoveConnection> connection);
static PortsList providedPorts(); static PortsList providedPorts();

View File

@ -16,7 +16,7 @@ void WeightedRandomNode::halt() {
NodeStatus WeightedRandomNode::tick() { NodeStatus WeightedRandomNode::tick() {
if (select_next) { if (select_next) {
const size_t children_count = children_nodes_.size(); size_t children_count = children_nodes_.size();
std::string weightString; std::string weightString;
@ -53,14 +53,18 @@ NodeStatus WeightedRandomNode::tick() {
} }
selected_child_index = i; selected_child_index = i;
std::cout<< "Selected child:" << selected_child_index <<std::endl;
select_next = false; select_next = false;
} }
TreeNode *current_child_node = children_nodes_[selected_child_index]; TreeNode *current_child_node = children_nodes_[selected_child_index];
const NodeStatus child_status = current_child_node->executeTick(); NodeStatus child_status = current_child_node->executeTick();
if (child_status != NodeStatus::RUNNING) { if (child_status != NodeStatus::RUNNING) {
select_next = true; select_next = true;
resetChildren();
} }
return child_status; return child_status;

View File

@ -1,7 +1,7 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<root main_tree_to_execute="actorTree"> <root main_tree_to_execute="actorTree">
<BehaviorTree ID="actorTree"> <BehaviorTree ID="actorTree">
<Control ID="WeightedRandom" weights="95,5"> <WeightedRandom weights="95,5">
<Sequence> <Sequence>
<SubTree ID="WorkOnBench"/> <SubTree ID="WorkOnBench"/>
<SubTree ID="DepositToShelf"/> <SubTree ID="DepositToShelf"/>
@ -10,7 +10,7 @@
<Action ID="GenerateXYPose" area="{unsafeArea}" pose="{actorTarget}"/> <Action ID="GenerateXYPose" area="{unsafeArea}" pose="{actorTarget}"/>
<Action ID="ActorMovement" animation_distance="1.5" animation_name="standing_walk" target="{actorTarget}"/> <Action ID="ActorMovement" animation_distance="1.5" animation_name="standing_walk" target="{actorTarget}"/>
</Sequence> </Sequence>
</Control> </WeightedRandom>
</BehaviorTree> </BehaviorTree>
<BehaviorTree ID="DepositToShelf"> <BehaviorTree ID="DepositToShelf">
<Sequence> <Sequence>

View File

@ -10,6 +10,32 @@
<Action ID="SetRobotVelocity" velocity="0.1"/> <Action ID="SetRobotVelocity" velocity="0.1"/>
<Action ID="SetRobotVelocity" velocity="1"/> <Action ID="SetRobotVelocity" velocity="1"/>
</IfThenElse> </IfThenElse>
<Control ID="InterruptableSequence">
<Fallback>
<Action ID="GenerateXYPose" area="{negativeYTable}" pose="{target}"/>
<Action ID="OffsetPose" input="{target}" offset="0,0,1.1" orientation="0,0,1,0" output="{target}"/>
<Action ID="RobotMove" target="{target}"/>
<Action ID="GenerateXYPose" area="{positiveYTable}" pose="{target}"/>
<Action ID="OffsetPose" input="{target}" offset="0,0,1.1" orientation="0,0,1,0" output="{target}"/>
<Action ID="RobotMove" target="{target}"/>
</Fallback>
</Control>
</ReactiveSequence>
</BehaviorTree>
<BehaviorTree ID="Slowdown">
<ReactiveSequence>
<Inverter>
<Condition ID="InAreaTest" area="{unsafeArea}" pose="{actorPos}"/>
</Inverter>
<IfThenElse>
<Condition ID="InAreaTest" area="{warningArea}" pose="{actorPos}"/>
<Action ID="SetRobotVelocity" velocity="0.1"/>
<Action ID="SetRobotVelocity" velocity="1"/>
</IfThenElse>
<SubTree ID="SafeTree" _autoremap="1"/>
</ReactiveSequence>
</BehaviorTree>
<BehaviorTree ID="SafeTree">
<Fallback> <Fallback>
<Control ID="InterruptableSequence"> <Control ID="InterruptableSequence">
<Action ID="GenerateXYPose" area="{negativeYTable}" pose="{target}"/> <Action ID="GenerateXYPose" area="{negativeYTable}" pose="{target}"/>
@ -20,6 +46,5 @@
<Action ID="RobotMove" target="{target}"/> <Action ID="RobotMove" target="{target}"/>
</Control> </Control>
</Fallback> </Fallback>
</ReactiveSequence>
</BehaviorTree> </BehaviorTree>
</root> </root>

@ -1 +1 @@
Subproject commit 55dd7680ff7234c825efa1dd0c104e5629448972 Subproject commit a295d3319727b3e5ad1b0fa7dbfd34f3369655cf

View File

@ -68,12 +68,8 @@ void ActorSystem::switchAnimation(EntityComponentManager &_ecm, char *animationN
} }
double Angle(ignition::math::Quaterniond a,ignition::math::Quaterniond b){ double Angle(ignition::math::Quaterniond a,ignition::math::Quaterniond b){
auto dot = fmin(abs(a.Dot(b)),1.0); auto dot = fmin(abs(a.Normalized().Dot(b.Normalized())),1.0);
if(dot > 0.999999){ return acos(dot);
return 0.0;
}else{
return acos(dot) * 2;
}
} }
void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) { void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) {
@ -184,6 +180,8 @@ void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ec
} }
movementDetails.rotateToEndDuration = Angle(movementDetails.targetDiff.Rot(),movementDetails.target.Rot()) / turnSpeed; movementDetails.rotateToEndDuration = Angle(movementDetails.targetDiff.Rot(),movementDetails.target.Rot()) / turnSpeed;
igndbg << movementDetails.rotateToTargetDuration << " " <<movementDetails.moveDuration << " " << movementDetails.rotateToEndDuration << std::endl;
} }
movementDetails.time += deltaTimeSeconds; movementDetails.time += deltaTimeSeconds;

View File

@ -1,7 +1,7 @@
import os import os
from ament_index_python import get_package_share_directory from ament_index_python import get_package_share_directory
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, ExecuteProcess, RegisterEventHandler from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, ExecuteProcess, RegisterEventHandler, TimerAction
from launch.event_handlers import OnProcessExit from launch.event_handlers import OnProcessExit
from launch_ros.actions import Node, SetParameter from launch_ros.actions import Node, SetParameter
from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.launch_description_sources import PythonLaunchDescriptionSource
@ -129,7 +129,12 @@ def generate_launch_description():
emulate_tty=True, emulate_tty=True,
), ),
TimerAction(
period=10.0,
actions=[
btree, btree,
]
),
IncludeLaunchDescription( IncludeLaunchDescription(
PythonLaunchDescriptionSource( PythonLaunchDescriptionSource(

View File

@ -30,7 +30,7 @@
<rot>180</rot> <rot>180</rot>
</plugin> </plugin>
<skin> <skin>
<filename>$(find ign_actor_plugin)/animation/walk.dae</filename> <filename>$(find ign_actor_plugin)/animation/standing_walk.dae</filename>
<scale>1.0</scale> <scale>1.0</scale>
</skin> </skin>

View File

@ -99,10 +99,12 @@ int main(int argc, char **argv) {
} }
if (newFeedback.state==IDLE) { if (newFeedback.state==IDLE) {
if(currentFeedback.state==ANIMATION && currentAnimationGoalPtr!=nullptr){ if(currentFeedback.state==ANIMATION && currentAnimationGoalPtr!=nullptr){
std::cout << "Finished Animation. " << std::endl;
currentAnimationGoalPtr->succeed(std::make_shared<ros_actor_action_server_msgs::action::Animation_Result>()); currentAnimationGoalPtr->succeed(std::make_shared<ros_actor_action_server_msgs::action::Animation_Result>());
currentAnimationGoalPtr = nullptr; currentAnimationGoalPtr = nullptr;
} }
if(currentFeedback.state==MOVEMENT && currentMovementGoalPtr!=nullptr){ if(currentFeedback.state==MOVEMENT && currentMovementGoalPtr!=nullptr){
std::cout << "Finished Movement. " << std::endl;
currentMovementGoalPtr->succeed(std::make_shared<ros_actor_action_server_msgs::action::Movement_Result>()); currentMovementGoalPtr->succeed(std::make_shared<ros_actor_action_server_msgs::action::Movement_Result>());
currentMovementGoalPtr = nullptr; currentMovementGoalPtr = nullptr;
} }
@ -120,14 +122,14 @@ int main(int argc, char **argv) {
rosMutex.lock(); rosMutex.lock();
if (currentFeedback.state == IDLE) { if (currentFeedback.state == IDLE) {
std::cout << "Accepting..." << std::endl; std::cout << "Accepting Animation..." << std::endl;
currentAction.animationSpeed = animationGoal->animation_speed; currentAction.animationSpeed = animationGoal->animation_speed;
strcpy(currentAction.animationName, animationGoal->animation_name.data()); strcpy(currentAction.animationName, animationGoal->animation_name.data());
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
} else { } else {
std::cout << "Rejecting..." << std::endl; std::cout << "Rejecting Animation..." << std::endl;
rosMutex.unlock(); rosMutex.unlock();
return rclcpp_action::GoalResponse::REJECT; return rclcpp_action::GoalResponse::REJECT;
} }
@ -137,9 +139,11 @@ int main(int argc, char **argv) {
return rclcpp_action::CancelResponse::REJECT; return rclcpp_action::CancelResponse::REJECT;
} else { } else {
rosMutex.lock(); rosMutex.lock();
std::cout << "Cancelling Animation..." << std::endl;
sendAction(actionQueue, &cancelAction); sendAction(actionQueue, &cancelAction);
waitForState(&currentFeedback, IDLE); waitForState(&currentFeedback, IDLE);
std::cout << "Cancelled Animation..." << std::endl;
rosMutex.unlock(); rosMutex.unlock();
return rclcpp_action::CancelResponse::ACCEPT; return rclcpp_action::CancelResponse::ACCEPT;
@ -161,7 +165,7 @@ int main(int argc, char **argv) {
[&currentAction, &currentFeedback](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal) { [&currentAction, &currentFeedback](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal) {
rosMutex.lock(); rosMutex.lock();
if (currentFeedback.state == IDLE) { if (currentFeedback.state == IDLE) {
std::cout << "Accepting..." << std::endl; std::cout << "Accepting Movement..." << std::endl;
currentAction.target = movementGoal->target; currentAction.target = movementGoal->target;
currentAction.animationSpeed = movementGoal->animation_distance; currentAction.animationSpeed = movementGoal->animation_distance;
@ -169,7 +173,7 @@ int main(int argc, char **argv) {
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
} else { } else {
std::cout << "Rejecting..." << std::endl; std::cout << "Rejecting Movement..." << std::endl;
rosMutex.unlock(); rosMutex.unlock();
return rclcpp_action::GoalResponse::REJECT; return rclcpp_action::GoalResponse::REJECT;
} }
@ -179,9 +183,11 @@ int main(int argc, char **argv) {
return rclcpp_action::CancelResponse::REJECT; return rclcpp_action::CancelResponse::REJECT;
} else { } else {
rosMutex.lock(); rosMutex.lock();
std::cout << "Cancelling Movement..." << std::endl;
sendAction(actionQueue, &cancelAction); sendAction(actionQueue, &cancelAction);
waitForState(&currentFeedback, IDLE); waitForState(&currentFeedback, IDLE);
std::cout << "Cancelled Movement..." << std::endl;
rosMutex.unlock(); rosMutex.unlock();
return rclcpp_action::CancelResponse::ACCEPT; return rclcpp_action::CancelResponse::ACCEPT;

View File

@ -1,2 +1,2 @@
ros2 action send_goal /ActorPlugin/animation ign_actor_plugin_msgs/action/Animation "{animation_name: 'walk', animation_speed: 1.0}" ros2 action send_goal /ActorPlugin/animation ign_actor_plugin_msgs/action/Animation "{animation_name: 'standing_walk', animation_speed: 1.0}"
ros2 action send_goal /ActorPlugin/movement ros_actor_action_server_msgs/action/Movement '{animation_name: "walk", animation_speed: 1.0, animation_distance: 1.5, target: {orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0}, position: {x: 2.0, y: 0.0, z: 0.0}}}' ros2 action send_goal /ActorPlugin/movement ros_actor_action_server_msgs/action/Movement '{animation_name: "standing_walk", animation_speed: 1.0, animation_distance: 1.5, target: {orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0}, position: {x: 2.0, y: 0.0, z: 0.0}}}'