diff --git a/src/btree_nodes/CMakeLists.txt b/src/btree/CMakeLists.txt
similarity index 95%
rename from src/btree_nodes/CMakeLists.txt
rename to src/btree/CMakeLists.txt
index 02a514b..f52bfd1 100644
--- a/src/btree_nodes/CMakeLists.txt
+++ b/src/btree/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
-project(btree_nodes)
+project(btree)
add_compile_options(-Wall -Wextra -Wpedantic)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
@@ -38,7 +38,6 @@ set(CPP_FILES
src/Tree.cpp
src/Extensions.cpp
src/nodes/WeightedRandomNode.cpp
- src/nodes/AmICalled.cpp
src/nodes/GenerateXYPose.cpp
src/nodes/RobotMove.cpp
src/nodes/MoveConnection.cpp
@@ -58,6 +57,8 @@ ament_target_dependencies(tree ${DEPENDENCIES})
install(TARGETS
tree
DESTINATION lib/${PROJECT_NAME})
+
+install(DIRECTORY trees DESTINATION share/${PROJECT_NAME})
if (BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
diff --git a/src/btree_nodes/nodes.xml b/src/btree/nodes.xml
similarity index 96%
rename from src/btree_nodes/nodes.xml
rename to src/btree/nodes.xml
index e681d8c..b329df9 100644
--- a/src/btree_nodes/nodes.xml
+++ b/src/btree/nodes.xml
@@ -70,7 +70,7 @@
- Chance to fail from 0 to 1
+ Chance to fail from 0 to 1
diff --git a/src/btree_nodes/package.xml b/src/btree/package.xml
similarity index 96%
rename from src/btree_nodes/package.xml
rename to src/btree/package.xml
index 9b68e79..90138ff 100644
--- a/src/btree_nodes/package.xml
+++ b/src/btree/package.xml
@@ -1,7 +1,7 @@
- btree_nodes
+ btree
0.0.0
TODO: Package description
bastian
diff --git a/src/btree_nodes/src/Area.h b/src/btree/src/Area.h
similarity index 100%
rename from src/btree_nodes/src/Area.h
rename to src/btree/src/Area.h
diff --git a/src/btree_nodes/src/Extensions.cpp b/src/btree/src/Extensions.cpp
similarity index 100%
rename from src/btree_nodes/src/Extensions.cpp
rename to src/btree/src/Extensions.cpp
diff --git a/src/btree_nodes/src/Tree.cpp b/src/btree/src/Tree.cpp
similarity index 98%
rename from src/btree_nodes/src/Tree.cpp
rename to src/btree/src/Tree.cpp
index f3fa6fa..918c7c4 100644
--- a/src/btree_nodes/src/Tree.cpp
+++ b/src/btree/src/Tree.cpp
@@ -8,7 +8,6 @@
#include
#include
#include "nodes/WeightedRandomNode.h"
-#include "nodes/AmICalled.h"
#include "nodes/GenerateXYPose.h"
#include "nodes/RobotMove.h"
#include "nodes/OffsetPose.h"
@@ -40,7 +39,6 @@ int main(int argc, char **argv) {
std::cout << "Registering nodes." << std::endl;
factory.registerNodeType("GenerateXYPose");
- factory.registerNodeType("AmICalled");
factory.registerNodeType("WeightedRandom");
factory.registerNodeType("OffsetPose");
diff --git a/src/btree_nodes/src/nodes/ActorAnimation.cpp b/src/btree/src/nodes/ActorAnimation.cpp
similarity index 84%
rename from src/btree_nodes/src/nodes/ActorAnimation.cpp
rename to src/btree/src/nodes/ActorAnimation.cpp
index 9484d18..eba6da3 100644
--- a/src/btree_nodes/src/nodes/ActorAnimation.cpp
+++ b/src/btree/src/nodes/ActorAnimation.cpp
@@ -12,7 +12,8 @@ ActorAnimation::ActorAnimation(const std::string &name, const BT::NodeConfigurat
BT::PortsList ActorAnimation::providedPorts() {
return {
- BT::InputPort("animation"),
+ BT::InputPort("animation_name"),
+ BT::InputPort("animation_speed"),
};
}
@@ -21,15 +22,16 @@ BT::NodeStatus ActorAnimation::onStart() {
ros_actor_action_server_msgs::action::Animation::Goal goal;
- auto res = getInput("animation", goal.animation_name);
-
- if (!res) {
+ if (!getInput("animation_name", goal.animation_name)) {
std::cerr << "[ no animation name specified ]" << std::endl;
- std::cout << res.error() << std::endl;
return BT::NodeStatus::FAILURE;
}
+
+ if (!getInput("animation_speed", goal.animation_speed)) {
+ goal.animation_speed=1.0;
+ }
- goal.animation_speed=1.0;
+
auto send_goal_options = Client::SendGoalOptions();
send_goal_options.result_callback = [=](const ClientGoalHandle::WrappedResult & parameter) {
diff --git a/src/btree_nodes/src/nodes/ActorAnimation.h b/src/btree/src/nodes/ActorAnimation.h
similarity index 100%
rename from src/btree_nodes/src/nodes/ActorAnimation.h
rename to src/btree/src/nodes/ActorAnimation.h
diff --git a/src/btree_nodes/src/nodes/ActorMovement.cpp b/src/btree/src/nodes/ActorMovement.cpp
similarity index 80%
rename from src/btree_nodes/src/nodes/ActorMovement.cpp
rename to src/btree/src/nodes/ActorMovement.cpp
index c967ba7..3a0362a 100644
--- a/src/btree_nodes/src/nodes/ActorMovement.cpp
+++ b/src/btree/src/nodes/ActorMovement.cpp
@@ -16,7 +16,8 @@ ActorMovement::ActorMovement(const std::string &name, const BT::NodeConfiguratio
BT::PortsList ActorMovement::providedPorts() {
return {
BT::InputPort>("target"),
- BT::InputPort("animation"),
+ BT::InputPort("animation_name"),
+ BT::InputPort("animation_distance"),
};
}
@@ -25,20 +26,24 @@ BT::NodeStatus ActorMovement::onStart() {
ros_actor_action_server_msgs::action::Movement::Goal goal;
- std::shared_ptr target;
- auto res = getInput>("target", target);
-
- if (!res) {
- std::cout << "[ no target available ]" << std::endl;
- std::cout << res.error() << std::endl;
+ {
+ std::shared_ptr target;
+ if (!getInput>("target", target)) {
+ std::cout << "[ no target given ]" << std::endl;
+ return BT::NodeStatus::FAILURE;
+ }
+ goal.target = *target;
+ }
+
+ if(!getInput("animation_distance", goal.animation_distance)){
+ goal.animation_distance = 1.0f;
+ }
+
+ if(!getInput("animation_name", goal.animation_name)){
+ std::cout << "[ no animation_name given ]" << std::endl;
return BT::NodeStatus::FAILURE;
}
- goal.animation_distance=1.5;
- goal.animation_name="walk";
- goal.animation_speed=1.0;
- goal.target = *target;
-
auto send_goal_options = Client::SendGoalOptions();
send_goal_options.feedback_callback = [&](__attribute__((unused)) std::shared_ptr> goal_handle, std::shared_ptr feedback) {
positionCallback(feedback);
diff --git a/src/btree_nodes/src/nodes/ActorMovement.h b/src/btree/src/nodes/ActorMovement.h
similarity index 100%
rename from src/btree_nodes/src/nodes/ActorMovement.h
rename to src/btree/src/nodes/ActorMovement.h
diff --git a/src/btree_nodes/src/nodes/GenerateXYPose.cpp b/src/btree/src/nodes/GenerateXYPose.cpp
similarity index 100%
rename from src/btree_nodes/src/nodes/GenerateXYPose.cpp
rename to src/btree/src/nodes/GenerateXYPose.cpp
diff --git a/src/btree_nodes/src/nodes/GenerateXYPose.h b/src/btree/src/nodes/GenerateXYPose.h
similarity index 100%
rename from src/btree_nodes/src/nodes/GenerateXYPose.h
rename to src/btree/src/nodes/GenerateXYPose.h
diff --git a/src/btree_nodes/src/nodes/InAreaTest.cpp b/src/btree/src/nodes/InAreaTest.cpp
similarity index 100%
rename from src/btree_nodes/src/nodes/InAreaTest.cpp
rename to src/btree/src/nodes/InAreaTest.cpp
diff --git a/src/btree_nodes/src/nodes/InAreaTest.h b/src/btree/src/nodes/InAreaTest.h
similarity index 100%
rename from src/btree_nodes/src/nodes/InAreaTest.h
rename to src/btree/src/nodes/InAreaTest.h
diff --git a/src/btree_nodes/src/nodes/InterruptableSequence.cpp b/src/btree/src/nodes/InterruptableSequence.cpp
similarity index 100%
rename from src/btree_nodes/src/nodes/InterruptableSequence.cpp
rename to src/btree/src/nodes/InterruptableSequence.cpp
diff --git a/src/btree_nodes/src/nodes/InterruptableSequence.h b/src/btree/src/nodes/InterruptableSequence.h
similarity index 100%
rename from src/btree_nodes/src/nodes/InterruptableSequence.h
rename to src/btree/src/nodes/InterruptableSequence.h
diff --git a/src/btree_nodes/src/nodes/MoveConnection.cpp b/src/btree/src/nodes/MoveConnection.cpp
similarity index 100%
rename from src/btree_nodes/src/nodes/MoveConnection.cpp
rename to src/btree/src/nodes/MoveConnection.cpp
diff --git a/src/btree_nodes/src/nodes/MoveConnection.h b/src/btree/src/nodes/MoveConnection.h
similarity index 100%
rename from src/btree_nodes/src/nodes/MoveConnection.h
rename to src/btree/src/nodes/MoveConnection.h
diff --git a/src/btree_nodes/src/nodes/OffsetPose.cpp b/src/btree/src/nodes/OffsetPose.cpp
similarity index 99%
rename from src/btree_nodes/src/nodes/OffsetPose.cpp
rename to src/btree/src/nodes/OffsetPose.cpp
index 236ffc8..79c14f1 100644
--- a/src/btree_nodes/src/nodes/OffsetPose.cpp
+++ b/src/btree/src/nodes/OffsetPose.cpp
@@ -47,4 +47,3 @@ BT::NodeStatus BT::OffsetPose::tick() {
return BT::NodeStatus::SUCCESS;
}
-
diff --git a/src/btree_nodes/src/nodes/OffsetPose.h b/src/btree/src/nodes/OffsetPose.h
similarity index 100%
rename from src/btree_nodes/src/nodes/OffsetPose.h
rename to src/btree/src/nodes/OffsetPose.h
diff --git a/src/btree_nodes/src/nodes/RandomFailure.cpp b/src/btree/src/nodes/RandomFailure.cpp
similarity index 81%
rename from src/btree_nodes/src/nodes/RandomFailure.cpp
rename to src/btree/src/nodes/RandomFailure.cpp
index b517fed..5916245 100644
--- a/src/btree_nodes/src/nodes/RandomFailure.cpp
+++ b/src/btree/src/nodes/RandomFailure.cpp
@@ -6,7 +6,7 @@
BT::NodeStatus BT::RandomFailure::tick() {
double failureChance;
- if (!getInput("failureChance", failureChance)) {
+ if (!getInput("failure_chance", failureChance)) {
std::cout << "could not get failure chance." << std::endl;
return NodeStatus::FAILURE;
}
@@ -19,7 +19,7 @@ BT::NodeStatus BT::RandomFailure::tick() {
}
BT::PortsList BT::RandomFailure::providedPorts() {
- return {InputPort("failureChance", "Chance to fail from 0 to 1")};
+ return {InputPort("failure_chance", "Chance to fail from 0 to 1")};
}
BT::RandomFailure::RandomFailure(
diff --git a/src/btree_nodes/src/nodes/RandomFailure.h b/src/btree/src/nodes/RandomFailure.h
similarity index 100%
rename from src/btree_nodes/src/nodes/RandomFailure.h
rename to src/btree/src/nodes/RandomFailure.h
diff --git a/src/btree_nodes/src/nodes/RobotMove.cpp b/src/btree/src/nodes/RobotMove.cpp
similarity index 100%
rename from src/btree_nodes/src/nodes/RobotMove.cpp
rename to src/btree/src/nodes/RobotMove.cpp
diff --git a/src/btree_nodes/src/nodes/RobotMove.h b/src/btree/src/nodes/RobotMove.h
similarity index 100%
rename from src/btree_nodes/src/nodes/RobotMove.h
rename to src/btree/src/nodes/RobotMove.h
diff --git a/src/btree_nodes/src/nodes/SetRobotVelocity.cpp b/src/btree/src/nodes/SetRobotVelocity.cpp
similarity index 100%
rename from src/btree_nodes/src/nodes/SetRobotVelocity.cpp
rename to src/btree/src/nodes/SetRobotVelocity.cpp
diff --git a/src/btree_nodes/src/nodes/SetRobotVelocity.h b/src/btree/src/nodes/SetRobotVelocity.h
similarity index 100%
rename from src/btree_nodes/src/nodes/SetRobotVelocity.h
rename to src/btree/src/nodes/SetRobotVelocity.h
diff --git a/src/btree_nodes/src/nodes/WeightedRandomNode.cpp b/src/btree/src/nodes/WeightedRandomNode.cpp
similarity index 100%
rename from src/btree_nodes/src/nodes/WeightedRandomNode.cpp
rename to src/btree/src/nodes/WeightedRandomNode.cpp
diff --git a/src/btree_nodes/src/nodes/WeightedRandomNode.h b/src/btree/src/nodes/WeightedRandomNode.h
similarity index 100%
rename from src/btree_nodes/src/nodes/WeightedRandomNode.h
rename to src/btree/src/nodes/WeightedRandomNode.h
diff --git a/src/btree_trees/trees/actorTreeCoex.xml b/src/btree/trees/actorTreeCoex.xml
similarity index 65%
rename from src/btree_trees/trees/actorTreeCoex.xml
rename to src/btree/trees/actorTreeCoex.xml
index 75abb4e..88290ed 100644
--- a/src/btree_trees/trees/actorTreeCoex.xml
+++ b/src/btree/trees/actorTreeCoex.xml
@@ -7,13 +7,13 @@
-
-
-
+
+
+
-
+
diff --git a/src/btree_trees/trees/actorTreeColab.xml b/src/btree/trees/actorTreeColab.xml
similarity index 94%
rename from src/btree_trees/trees/actorTreeColab.xml
rename to src/btree/trees/actorTreeColab.xml
index 5eb0411..9c1cfe2 100644
--- a/src/btree_trees/trees/actorTreeColab.xml
+++ b/src/btree/trees/actorTreeColab.xml
@@ -14,12 +14,12 @@
-
+
-
+
diff --git a/src/btree_trees/trees/actorTreeCoop.xml b/src/btree/trees/actorTreeCoop.xml
similarity index 94%
rename from src/btree_trees/trees/actorTreeCoop.xml
rename to src/btree/trees/actorTreeCoop.xml
index 5eb0411..9c1cfe2 100644
--- a/src/btree_trees/trees/actorTreeCoop.xml
+++ b/src/btree/trees/actorTreeCoop.xml
@@ -14,12 +14,12 @@
-
+
-
+
diff --git a/src/btree_trees/trees/robotTreeCoex.xml b/src/btree/trees/robotTreeCoex.xml
similarity index 100%
rename from src/btree_trees/trees/robotTreeCoex.xml
rename to src/btree/trees/robotTreeCoex.xml
diff --git a/src/btree_trees/trees/robotTreeColab.xml b/src/btree/trees/robotTreeColab.xml
similarity index 95%
rename from src/btree_trees/trees/robotTreeColab.xml
rename to src/btree/trees/robotTreeColab.xml
index 0a30d8d..5bc3596 100644
--- a/src/btree_trees/trees/robotTreeColab.xml
+++ b/src/btree/trees/robotTreeColab.xml
@@ -16,11 +16,11 @@
-
+
-
+
diff --git a/src/btree_trees/trees/robotTreeCoop.xml b/src/btree/trees/robotTreeCoop.xml
similarity index 100%
rename from src/btree_trees/trees/robotTreeCoop.xml
rename to src/btree/trees/robotTreeCoop.xml
diff --git a/src/btree_nodes/src/nodes/AmICalled.cpp b/src/btree_nodes/src/nodes/AmICalled.cpp
deleted file mode 100644
index 714a474..0000000
--- a/src/btree_nodes/src/nodes/AmICalled.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-//
-// Created by bastian on 26.03.22.
-//
-
-#include "AmICalled.h"
-
-BT::AmICalled::AmICalled(const std::string &name, const BT::NodeConfiguration &config) :
- ConditionNode(name, config) {}
-
-BT::PortsList BT::AmICalled::providedPorts() {
- return {InputPort("called")};
-}
-
-BT::NodeStatus BT::AmICalled::tick() {
- bool called;
- if (!getInput("called", called)) {
- return NodeStatus::FAILURE;
- }
- if (called) {
- return NodeStatus::SUCCESS;
- }
- return NodeStatus::FAILURE;
-}
diff --git a/src/btree_nodes/src/nodes/AmICalled.h b/src/btree_nodes/src/nodes/AmICalled.h
deleted file mode 100644
index 9daf834..0000000
--- a/src/btree_nodes/src/nodes/AmICalled.h
+++ /dev/null
@@ -1,22 +0,0 @@
-//
-// Created by bastian on 26.03.22.
-//
-
-#ifndef BUILD_AMICALLED_H
-#define BUILD_AMICALLED_H
-
-#include
-
-namespace BT {
-
- class AmICalled : public ConditionNode {
- public:
- AmICalled(const std::string &name, const NodeConfiguration &config);
-
- static PortsList providedPorts();
-
- NodeStatus tick() override;
- };
-
-}
-#endif //BUILD_AMICALLED_H
diff --git a/src/btree_trees/package.xml b/src/btree_trees/package.xml
deleted file mode 100644
index d23d9b1..0000000
--- a/src/btree_trees/package.xml
+++ /dev/null
@@ -1,13 +0,0 @@
-
- btree_trees
- 0.244.1
- Trees for the simulation
- Apache 2.0
- Bastian Hofmann
-
- ament_cmake
-
-
- ament_cmake
-
-
diff --git a/src/btree_trees/CMakeLists.txt b/src/controller_test/CMakeLists.txt
similarity index 64%
rename from src/btree_trees/CMakeLists.txt
rename to src/controller_test/CMakeLists.txt
index 518bfb2..b575dd2 100644
--- a/src/btree_trees/CMakeLists.txt
+++ b/src/controller_test/CMakeLists.txt
@@ -1,17 +1,28 @@
cmake_minimum_required(VERSION 3.8)
-project(btree_trees)
+project(controller_test)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
+set(CMAKE_CXX_STANDARD_REQUIRED ON)
+set(CMAKE_POSITION_INDEPENDENT_CODE ON)
# find dependencies
find_package(ament_cmake REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(moveit_ros_planning_interface REQUIRED)
+find_package(control_msgs REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package( REQUIRED)
-install(DIRECTORY trees DESTINATION share/${PROJECT_NAME})
+add_executable(move src/test.cpp)
+set_property(TARGET move PROPERTY CXX_STANDARD 17)
+ament_target_dependencies(move rclcpp moveit_ros_planning_interface control_msgs)
+
+install(TARGETS
+ move
+ DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
diff --git a/src/controller_test/package.xml b/src/controller_test/package.xml
new file mode 100644
index 0000000..0f4f1d8
--- /dev/null
+++ b/src/controller_test/package.xml
@@ -0,0 +1,23 @@
+
+
+
+ controller_test
+ 0.1.0
+
+ Test for Moveit on IISY
+
+ bastian
+ bastian
+ TODO: License declaration
+
+ ament_cmake
+
+ rclcpp
+ geometry_msgs
+ moveit_ros_planning_interface
+
+
+ ament_cmake
+
+
+
diff --git a/src/controller_test/src/test.cpp b/src/controller_test/src/test.cpp
new file mode 100644
index 0000000..e169cea
--- /dev/null
+++ b/src/controller_test/src/test.cpp
@@ -0,0 +1,203 @@
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+
+std::shared_ptr node;
+
+void common_goal_response(
+ const rclcpp_action::ClientGoalHandle
+ ::SharedPtr& future)
+{
+ RCLCPP_DEBUG(
+ node->get_logger(), "common_goal_response time: %f",
+ rclcpp::Clock().now().seconds());
+ auto goal_handle = future.get();
+ if (!goal_handle) {
+ printf("Goal rejected\n");
+ } else {
+ printf("Goal accepted\n");
+ }
+}
+
+void common_result_response(
+ const rclcpp_action::ClientGoalHandle
+ ::WrappedResult & result)
+{
+ printf("common_result_response time: %f\n", rclcpp::Clock().now().seconds());
+ switch (result.code) {
+ case rclcpp_action::ResultCode::SUCCEEDED:
+ printf("SUCCEEDED result code\n");
+ break;
+ case rclcpp_action::ResultCode::ABORTED:
+ printf("Goal was aborted\n");
+ return;
+ case rclcpp_action::ResultCode::CANCELED:
+ printf("Goal was canceled\n");
+ return;
+ default:
+ printf("Unknown result code\n");
+ return;
+ }
+}
+
+void common_feedback(
+ const rclcpp_action::ClientGoalHandle::SharedPtr&,
+ const std::shared_ptr& feedback)
+{
+ std::cout << "feedback->desired.positions :";
+ for (auto & x : feedback->desired.positions) {
+ std::cout << x << "\t";
+ }
+ std::cout << std::endl;
+ std::cout << "feedback->desired.velocities :";
+ for (auto & x : feedback->desired.velocities) {
+ std::cout << x << "\t";
+ }
+ std::cout << std::endl;
+}
+
+int main(int argc, char * argv[])
+{
+ rclcpp::init(argc, argv);
+
+ node = std::make_shared("trajectory_test_node");
+
+ std::cout << "node created" << std::endl;
+
+ rclcpp_action::Client::SharedPtr action_client;
+ action_client = rclcpp_action::create_client(
+ node->get_node_base_interface(),
+ node->get_node_graph_interface(),
+ node->get_node_logging_interface(),
+ node->get_node_waitables_interface(),
+ "/arm_controller/follow_joint_trajectory");
+
+ bool response =
+ action_client->wait_for_action_server(std::chrono::seconds(10));
+ if (!response) {
+ throw std::runtime_error("could not get action server");
+ }
+ std::cout << "Created action server" << std::endl;
+
+ std::vector joint_names = {
+ "base_rot",
+ "base_link1_joint",
+ "link1_link2_joint",
+ "link2_rot",
+ "link2_link3_joint",
+ "link3_rot"
+ };
+
+ std::vector points;
+ trajectory_msgs::msg::JointTrajectoryPoint point;
+ point.time_from_start = rclcpp::Duration::from_seconds(0.0); // start asap
+ point.positions.resize(joint_names.size());
+
+ point.positions[0] = 0.0;
+ point.positions[1] = 0.0;
+ point.positions[2] = 0.0;
+ point.positions[3] = 0.0;
+ point.positions[4] = 0.0;
+ point.positions[5] = 0.0;
+
+ trajectory_msgs::msg::JointTrajectoryPoint point2;
+ point2.time_from_start = rclcpp::Duration::from_seconds(1.0);
+ point2.positions.resize(joint_names.size());
+
+ point2.positions[0] = -1.0;
+ point2.positions[1] = 0.0;
+ point2.positions[2] = 0.0;
+ point2.positions[3] = 0.0;
+ point2.positions[4] = 0.0;
+ point2.positions[5] = 0.0;
+
+ trajectory_msgs::msg::JointTrajectoryPoint point3;
+ point3.time_from_start = rclcpp::Duration::from_seconds(2.0);
+ point3.positions.resize(joint_names.size());
+
+ point3.positions[0] = 1.0;
+ point3.positions[1] = 0.0;
+ point3.positions[2] = 0.0;
+ point3.positions[3] = 0.0;
+ point3.positions[4] = 0.0;
+ point3.positions[5] = 0.0;
+
+ trajectory_msgs::msg::JointTrajectoryPoint point4;
+ point4.time_from_start = rclcpp::Duration::from_seconds(3.0);
+ point4.positions.resize(joint_names.size());
+
+ point4.positions[0] = 0.0;
+ point4.positions[1] = 0.0;
+ point4.positions[2] = M_PI/2;
+ point4.positions[3] = 0.0;
+ point4.positions[4] = 0.0;
+ point4.positions[5] = 0.0;
+
+ points.push_back(point);
+ points.push_back(point2);
+ points.push_back(point3);
+ points.push_back(point4);
+
+ rclcpp_action::Client::SendGoalOptions opt;
+ opt.goal_response_callback = [](std::shared_ptr> goal){
+ if(goal->get_status()==rclcpp_action::GoalStatus::STATUS_ACCEPTED){
+ RCLCPP_DEBUG(
+ node->get_logger(), "common_goal_response accepted: %f",
+ rclcpp::Clock().now().seconds());
+ }else{
+ RCLCPP_DEBUG(
+ node->get_logger(), "common_goal_response rejected: %f",
+ rclcpp::Clock().now().seconds());
+ }
+ };
+ //opt.goal_response_callback = [](auto && PH1) { return common_goal_response(std::forward(PH1)); };
+ opt.result_callback = [](auto && PH1) { return common_result_response(std::forward(PH1)); };
+ opt.feedback_callback = [](auto && PH1, auto && PH2) { return common_feedback(std::forward(PH1), std::forward(PH2)); };
+
+ control_msgs::action::FollowJointTrajectory_Goal goal_msg;
+ goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds(1.0);
+ goal_msg.trajectory.joint_names = joint_names;
+ goal_msg.trajectory.points = points;
+
+ auto goal_handle_future = action_client->async_send_goal(goal_msg, opt);
+
+ if (rclcpp::spin_until_future_complete(node, goal_handle_future) !=
+ rclcpp::FutureReturnCode::SUCCESS)
+ {
+ RCLCPP_ERROR(node->get_logger(), "send goal call failed :(");
+ return 1;
+ }
+ RCLCPP_ERROR(node->get_logger(), "send goal call ok :)");
+
+ const rclcpp_action::ClientGoalHandle::SharedPtr&
+ goal_handle = goal_handle_future.get();
+ if (!goal_handle) {
+ RCLCPP_ERROR(node->get_logger(), "Goal was rejected by server");
+ return 1;
+ }
+ RCLCPP_ERROR(node->get_logger(), "Goal was accepted by server");
+
+ // Wait for the server to be done with the goal
+ auto result_future = action_client->async_get_result(goal_handle);
+ RCLCPP_INFO(node->get_logger(), "Waiting for result");
+ if (rclcpp::spin_until_future_complete(node, result_future) !=
+ rclcpp::FutureReturnCode::SUCCESS)
+ {
+ RCLCPP_ERROR(node->get_logger(), "get result call failed :(");
+ return 1;
+ }
+
+ std::cout << "async_send_goal" << std::endl;
+
+ rclcpp::shutdown();
+
+ return 0;
+}
\ No newline at end of file
diff --git a/src/ign_actor_plugin/src/ActorSystem.cpp b/src/ign_actor_plugin/src/ActorSystem.cpp
index 048796a..f4f9195 100644
--- a/src/ign_actor_plugin/src/ActorSystem.cpp
+++ b/src/ign_actor_plugin/src/ActorSystem.cpp
@@ -124,11 +124,12 @@ void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ec
auto animationTimeComponent = _ecm.Component(this->entity);
auto newTime = animationTimeComponent->Data() + _info.dt;
auto newTimeSeconds = std::chrono::duration(newTime).count();
-
- feedback.progress = newTimeSeconds / duration;
+
+ auto progress = newTimeSeconds / (duration/animation_speed);
+ feedback.progress = progress;
sendFeedback();
- if (newTimeSeconds >= duration) {
+ if (progress >= 1.0) {
igndbg << "Animation " << animation_name << " finished." << std::endl;
nextState = IDLE;
feedback.progress = 0.0f;
@@ -166,7 +167,7 @@ void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ec
if(movementDetails.targetDiff.Pos().Length() >= 0.001){
movementDetails.targetDiff.Rot() = ignition::math::Quaterniond::EulerToQuaternion(0.0, 0.0, atan2(movementDetails.targetDiff.Pos().Y(), movementDetails.targetDiff.Pos().X()));
movementDetails.rotateToTargetDuration = Angle(actorPose.Rot(),movementDetails.targetDiff.Rot()) / turnSpeed;
- movementDetails.moveDuration = movementDetails.targetDiff.Pos().Length() / animation_distance * duration;
+ movementDetails.moveDuration = movementDetails.targetDiff.Pos().Length() / animation_speed * duration;
}else{
movementDetails.targetDiff.Rot() = movementDetails.start.Rot();
movementDetails.rotateToTargetDuration = 0.0;
@@ -190,6 +191,7 @@ void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ec
if (movementDetails.state == movementDetails.ROTATE_TO_TARGET){
if(movementDetails.stepTime<=movementDetails.rotateToTargetDuration){
+ newTime = newTime.zero();
actorPose.Rot() = ignition::math::Quaterniond::Slerp(movementDetails.stepTime/movementDetails.rotateToTargetDuration,movementDetails.start.Rot(),movementDetails.targetDiff.Rot(),true);
}else{
actorPose.Rot() = movementDetails.targetDiff.Rot();
@@ -311,8 +313,7 @@ void ActorSystem::messageQueueInterface(const char name[256]) {
threadMutex.lock();
strcpy(animation_name, receivedAction.animationName);
- // animation_speed = receivedAction.animationSpeed;
- animation_distance = receivedAction.animationDistance;
+ animation_speed = receivedAction.animationSpeed;
movementDetails.target.Pos().Set(receivedAction.target.position.x, receivedAction.target.position.y, receivedAction.target.position.z);
movementDetails.target.Rot().Set(receivedAction.target.orientation.w, receivedAction.target.orientation.x, receivedAction.target.orientation.y, receivedAction.target.orientation.z);
nextState = receivedAction.state;
diff --git a/src/ign_actor_plugin/src/ActorSystem.hpp b/src/ign_actor_plugin/src/ActorSystem.hpp
index 091d1f0..83644a3 100644
--- a/src/ign_actor_plugin/src/ActorSystem.hpp
+++ b/src/ign_actor_plugin/src/ActorSystem.hpp
@@ -59,7 +59,7 @@ class ActorSystem : public System,
private:
ignition::math::Pose3d startPose = ignition::math::Pose3d::Zero;
ignition::math::Pose3d target_pose;
- double animation_distance;
+ double animation_speed;
char animation_name[256];
ActorPluginState nextState,currentState,lastState;
double duration{};
diff --git a/src/ign_world/launch/gazebo_controller_launch.py b/src/ign_world/launch/gazebo_controller_launch.py
index 4db0447..4eaaa54 100644
--- a/src/ign_world/launch/gazebo_controller_launch.py
+++ b/src/ign_world/launch/gazebo_controller_launch.py
@@ -31,6 +31,52 @@ def generate_launch_description():
],
output='screen'
)
+
+ btree = Node(
+ package='btree',
+ executable='tree',
+ output='both',
+ parameters=[
+ {
+ "trees": [
+ get_package_share_directory('btree')+'/trees/actorTreeCoex.xml',
+ get_package_share_directory('btree')+'/trees/robotTreeCoex.xml'
+ ],
+ "areas": [
+ "safeArea",
+ "1, 3.5 |" +
+ "1, 7 |" +
+ "3, 3.5 |" +
+ "7, 7 |" +
+ "3, -1 |" +
+ "7, -1",
+ "warningArea",
+ "-1, 2.5 |" +
+ "-1, 3.5 |" +
+ "2, 2.5 |" +
+ "3, 3.5 |" +
+ "2, -1 |" +
+ "3, -1",
+ "unsafeArea",
+ "-1, 1.5 |" +
+ "-1, 2.5 |" +
+ "1, 1.5 |" +
+ "2, 2.5 |" +
+ "1, -1 |" +
+ "2, -1",
+ "negativeYTable",
+ "0.3, -0.25 |" +
+ "-0.3, -0.25 |" +
+ "0, -0.4",
+ "positiveYTable",
+ "0.3, 0.25 |" +
+ "-0.3, 0.25 |" +
+ "0, 0.4"
+ ]
+ },
+ ],
+ emulate_tty=True,
+ )
return LaunchDescription([
IncludeLaunchDescription(
@@ -66,51 +112,7 @@ def generate_launch_description():
emulate_tty=True,
),
- Node(
- package='btree_nodes',
- executable='tree',
- output='both',
- parameters=[
- {
- "trees": [
- get_package_share_directory('btree_trees')+'/trees/actorTreeCoex.xml',
- get_package_share_directory('btree_trees')+'/trees/robotTreeCoex.xml'
- ],
- "areas": [
- "safeArea",
- "1, 3.5 |" +
- "1, 7 |" +
- "3, 3.5 |" +
- "7, 7 |" +
- "3, -1 |" +
- "7, -1",
- "warningArea",
- "-1, 2.5 |" +
- "-1, 3.5 |" +
- "2, 2.5 |" +
- "3, 3.5 |" +
- "2, -1 |" +
- "3, -1",
- "unsafeArea",
- "-1, 1.5 |" +
- "-1, 2.5 |" +
- "1, 1.5 |" +
- "2, 2.5 |" +
- "1, -1 |" +
- "2, -1",
- "negativeYTable",
- "0.3, -0.25 |" +
- "-0.3, -0.25 |" +
- "0, -0.4",
- "positiveYTable",
- "0.3, 0.25 |" +
- "-0.3, 0.25 |" +
- "0, 0.4"
- ]
- },
- ],
- emulate_tty=True,
- ),
+ btree,
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
diff --git a/src/iisy_config/config/iisy.urdf b/src/iisy_config/config/iisy.urdf
index c743fcb..0021227 100644
--- a/src/iisy_config/config/iisy.urdf
+++ b/src/iisy_config/config/iisy.urdf
@@ -27,7 +27,7 @@
-
+
@@ -45,7 +45,7 @@
-
+
@@ -62,7 +62,7 @@
-
+
@@ -80,7 +80,7 @@
-
+
@@ -97,7 +97,7 @@
-
+
@@ -114,7 +114,7 @@
-
+
@@ -131,7 +131,7 @@
-
+
@@ -155,31 +155,31 @@
-
-
+
+
-
-
+
+
-
-
+
+
-
+
@@ -187,16 +187,16 @@
-
-
+
+
-
-
+
+
transmission_interface/SimpleTransmission
diff --git a/src/ros_actor_action_server/src/Server.cpp b/src/ros_actor_action_server/src/Server.cpp
index ece8c8a..f59f54e 100644
--- a/src/ros_actor_action_server/src/Server.cpp
+++ b/src/ros_actor_action_server/src/Server.cpp
@@ -122,6 +122,7 @@ int main(int argc, char **argv) {
if (currentFeedback.state == IDLE) {
std::cout << "Accepting..." << std::endl;
+ currentAction.animationSpeed = animationGoal->animation_speed;
strcpy(currentAction.animationName, animationGoal->animation_name.data());
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
@@ -163,7 +164,7 @@ int main(int argc, char **argv) {
std::cout << "Accepting..." << std::endl;
currentAction.target = movementGoal->target;
- currentAction.animationDistance = movementGoal->animation_distance;
+ currentAction.animationSpeed = movementGoal->animation_distance;
strcpy(currentAction.animationName, movementGoal->animation_name.data());
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
diff --git a/src/ros_actor_action_server_msgs/action/Movement.action b/src/ros_actor_action_server_msgs/action/Movement.action
index 0a750f3..23309a5 100644
--- a/src/ros_actor_action_server_msgs/action/Movement.action
+++ b/src/ros_actor_action_server_msgs/action/Movement.action
@@ -1,5 +1,4 @@
string animation_name
-float32 animation_speed
float32 animation_distance
geometry_msgs/Pose target
---
diff --git a/src/ros_actor_message_queue_msgs/include/ros_actor_message_queue_msgs/MessageTypes.hpp b/src/ros_actor_message_queue_msgs/include/ros_actor_message_queue_msgs/MessageTypes.hpp
index bd9be93..5104d4b 100644
--- a/src/ros_actor_message_queue_msgs/include/ros_actor_message_queue_msgs/MessageTypes.hpp
+++ b/src/ros_actor_message_queue_msgs/include/ros_actor_message_queue_msgs/MessageTypes.hpp
@@ -1,19 +1,21 @@
#include
namespace ros_actor_message_queue_msgs{
+
enum ActorPluginState{
- SETUP,IDLE,ANIMATION,MOVEMENT
- };
+ SETUP,IDLE,ANIMATION,MOVEMENT
+};
struct FeedbackMessage{
- ActorPluginState state;
- float progress;
- geometry_msgs::msg::Pose current;
+ ActorPluginState state;
+ float progress;
+ geometry_msgs::msg::Pose current;
};
struct ActionMessage{
- ActorPluginState state;
- geometry_msgs::msg::Pose target;
- float animationSpeed = 1.0f,animationDistance = 1.0f;
- char animationName[256];
+ ActorPluginState state;
+ geometry_msgs::msg::Pose target;
+ float animationSpeed = 1.0f;
+ char animationName[256];
};
+
}
\ No newline at end of file