rebuild move logic

This commit is contained in:
Splinter1984 2021-12-20 20:42:14 +07:00
parent eca508ef8f
commit c4c3956f5a
10 changed files with 110 additions and 81 deletions

View file

@ -0,0 +1,21 @@
{
"configurations": [
{
"browse": {
"databaseFilename": "",
"limitSymbolsToIncludedHeaders": true
},
"includePath": [
"/home/splinter1984/robas_ws/install/moveit_visual_tools/include/**",
"/home/splinter1984/robas_ws/install/rviz_visual_tools/include/**",
"/opt/ros/foxy/include/**",
"/home/splinter1984/robas_ws/src/moveit_visual_tools/include/**",
"/home/splinter1984/robas_ws/src/robossembler-ros2/rasms_manipulator/include/**",
"/home/splinter1984/robas_ws/src/rviz_visual_tools/include/**",
"/usr/include/**"
],
"name": "ROS"
}
],
"version": 4
}

View file

@ -0,0 +1,9 @@
{
"python.autoComplete.extraPaths": [
"/opt/ros/foxy/lib/python3.8/site-packages"
],
"python.analysis.extraPaths": [
"/opt/ros/foxy/lib/python3.8/site-packages"
],
"ros.distro": "foxy"
}

View file

@ -26,8 +26,7 @@ endif()
set(dependencies set(dependencies
rclcpp rclcpp
rclcpp_action rclcpp_action
geometry_msgs geometry_msgs tf2_geometry_msgs
tf2_geometry_msgs
moveit_msgs moveit_msgs
moveit_core moveit_core
moveit_ros_planning moveit_ros_planning
@ -52,13 +51,17 @@ foreach(bt_plugin ${plugin_libs})
target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT) target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT)
endforeach() endforeach()
add_executable(assemble_controller_node src/assemble_controller_node.cpp) add_executable(rasms_controller_node src/rasms_controller_node.cpp)
ament_target_dependencies(assemble_controller_node ${dependencies}) ament_target_dependencies(rasms_controller_node ${dependencies})
add_executable(rasms_action_node src/rasms_action_node.cpp)
ament_target_dependencies(rasms_action_node ${dependencies})
install(DIRECTORY launch pddl behavior_trees_xml config DESTINATION share/${PROJECT_NAME}) install(DIRECTORY launch pddl behavior_trees_xml config DESTINATION share/${PROJECT_NAME})
install(TARGETS install(TARGETS
assemble_controller_node rasms_controller_node
rasms_action_node
${plugin_libs} ${plugin_libs}
ARCHIVE DESTINATION lib ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib LIBRARY DESTINATION lib

View file

@ -1,7 +1,8 @@
move_1: move:
ros__parameters: ros__parameters:
plugins: plugins:
- rasms_move_bt_node - rasms_move_bt_node
waypoints: ["one"] waypoints: ["one", "two"]
waypoints_coords: waypoints_coords:
one: [0.2, 0.2, 0.2] one: [0.0, 0.0, 0.0]
two: [0.2, 0.2, 0.2]

View file

@ -35,7 +35,7 @@ def generate_launch_description():
move_1 = Node( move_1 = Node(
package='plansys2_bt_actions', package='plansys2_bt_actions',
executable='bt_action_node', executable='bt_action_node',
name='move_1', name='move',
namespace=namespace, namespace=namespace,
output='screen', output='screen',
parameters=[ parameters=[

View file

@ -22,13 +22,14 @@
;; Actions ;;;;;;;;;;;;;;;;;;;;;;;;;;;; ;; Actions ;;;;;;;;;;;;;;;;;;;;;;;;;;;;
(:durative-action move (:durative-action move
:parameters (?r - robot ?z - zone) :parameters (?r - robot ?z1 ?z2 - zone)
:duration ( = ?duration 5) :duration ( = ?duration 5)
:condition (and :condition (and
(over all(robot_at ?r ?z)) (at start(robot_at ?r ?z1))
) )
:effect (and :effect (and
(at end(robot_moved ?r ?z)) (at start(not(robot_at ?r ?z1)))
(at end(robot_at ?r ?z2))
) )
) )

View file

@ -32,15 +32,8 @@ namespace rasms_manipulation
node->get_parameter_or("waypoints", wp_names, {}); node->get_parameter_or("waypoints", wp_names, {});
for (auto &wp : wp_names) for (auto &wp : wp_names)
{
try
{ {
node->declare_parameter("waypoint_coords." + wp); node->declare_parameter("waypoint_coords." + wp);
}
catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException &ex)
{
std::cerr << ex.what() << '\n';
}
std::vector<double> coords; std::vector<double> coords;
if (node->get_parameter_or("waypoint_coords." + wp, coords, {})) if (node->get_parameter_or("waypoint_coords." + wp, coords, {}))
@ -77,35 +70,36 @@ namespace rasms_manipulation
std::cerr << "No coordinate for waypoint [" << goal << "]" << std::endl; std::cerr << "No coordinate for waypoint [" << goal << "]" << std::endl;
} }
//Setup MoveIt interface for planning
static const std::string PLANNING_GROUP = "rasms_arm_group"; static const std::string PLANNING_GROUP = "rasms_arm_group";
moveit::planning_interface::MoveGroupInterface move_group(node, PLANNING_GROUP); moveit::planning_interface::MoveGroupInterface move_group_interface(node, PLANNING_GROUP);
// move_group->setStartState(*move_group->getCurrentState());
// Raw pointers are frequently used to refer to the planning group for improved performance.
const moveit::core::JointModelGroup* joint_model_group =
move_group_interface.getCurrentState()->getJointModelGroup(PLANNING_GROUP);
// move_group_interface->setStartState(*move_group_interface->getCurrentState());
/*---------- /*----------
00823 // pose goal; 00823 // pose goal;
00824 // for each link we have a set of possible goal locations; 00824 // for each link we have a set of possible goal locations;
00825 std::map<std::string, std::vector<geometry_msgs::PoseStamped> > pose_targets_; 00825 std::map<std::string, std::vector<geometry_msgs::PoseStamped> > pose_targets_;
----------*/ ----------*/
geometry_msgs::msg::PoseStamped goal_pos; geometry_msgs::msg::Pose goal_pos;
goal_pos.header.frame_id = "base"; goal_pos.orientation.w = 1.0;
goal_pos.pose.position.x = pose2moveit.position.x; goal_pos.position.x = pose2moveit.position.x;
goal_pos.pose.position.y = pose2moveit.position.y; goal_pos.position.y = pose2moveit.position.y;
goal_pos.pose.position.z = pose2moveit.position.z; goal_pos.position.z = pose2moveit.position.z;
// goal_pos.pose.orientation = pose2moveit.orientation; move_group_interface.setPoseTarget(goal_pos);
move_group.setPoseTarget(goal_pos, "link6");
moveit::planning_interface::MoveGroupInterface::Plan my_plan; moveit::planning_interface::MoveGroupInterface::Plan my_plan;
bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS); bool success = (move_group_interface.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
if (success) if (success)
{ {
//RCLCPP_INFO("Planning successful"); //RCLCPP_INFO("Planning successful");
// move_group->setStartStateToCurrentState(); // move_group_interface->setStartStateToCurrentState();
move_group.execute(my_plan); move_group_interface.execute(my_plan);
move_group.move(); move_group_interface.move();
}
else
{
return;
} }
} }

View file

@ -26,7 +26,7 @@ class AssembleAction : public plansys2::ActionExecutorClient
{ {
public: public:
AssembleAction() AssembleAction()
: plansys2::ActionExecutorClient("assemble", 500ms) : plansys2::ActionExecutorClient("rasms_move", 500ms)
{ {
progress_ = 0.0; progress_ = 0.0;
} }
@ -36,16 +36,16 @@ private:
{ {
if (progress_ < 1.0) { if (progress_ < 1.0) {
progress_ += 0.05; progress_ += 0.05;
send_feedback(progress_, "Assemble running"); send_feedback(progress_, "Move running");
} else { } else {
finish(true, 1.0, "Assemble completed"); finish(true, 1.0, "Move completed");
progress_ = 0.0; progress_ = 0.0;
std::cout << std::endl; std::cout << std::endl;
} }
std::cout << "\r\e[K" << std::flush; std::cout << "\r\e[K" << std::flush;
std::cout << "Assemble ... [" << std::min(100.0, progress_ * 100.0) << "%] " << std::cout << "Moving ... [" << std::min(100.0, progress_ * 100.0) << "%] " <<
std::flush; std::flush;
} }
@ -57,7 +57,7 @@ int main(int argc, char ** argv)
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
auto node = std::make_shared<AssembleAction>(); auto node = std::make_shared<AssembleAction>();
node->set_parameter(rclcpp::Parameter("action_name", "assemble")); node->set_parameter(rclcpp::Parameter("action_name", "move"));
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE); node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
rclcpp::spin(node->get_node_base_interface()); rclcpp::spin(node->get_node_base_interface());

View file

@ -1,3 +1,17 @@
// Copyright 2019 Intelligent Robotics Lab
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <memory> #include <memory>
#include <random> #include <random>
@ -11,11 +25,13 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp_action/rclcpp_action.hpp"
class RasmsController: public rclcpp::Node class RasmsController : public rclcpp::Node
{ {
public: public:
RasmsController(): rclcpp::Node("rasms_controller") RasmsController()
{} : rclcpp::Node("rasms_controller")
{
}
void init() void init()
{ {
@ -36,17 +52,19 @@ public:
{ {
RCLCPP_ERROR(get_logger(), "Error starting a new plan (first)"); RCLCPP_ERROR(get_logger(), "Error starting a new plan (first)");
} }
} else { }
else
{
RCLCPP_ERROR_STREAM( RCLCPP_ERROR_STREAM(
this->get_logger(), "Could not find plan to reach goal " << this->get_logger(), "Could not find plan to reach goal " << parser::pddl::toString(problem_expert_->getGoal()));
parser::pddl::toString(problem_expert_->getGoal()));
} }
} }
void init_knowledge() void init_knowledge()
{ {
problem_expert_->addInstance(plansys2::Instance{"rasms", "robot"}); problem_expert_->addInstance(plansys2::Instance{"rasms", "robot"});
problem_expert_->setGoal(plansys2::Goal("robot moved")); problem_expert_->addInstance(plansys2::Instance{"one", "zone"});
problem_expert_->addInstance(plansys2::Instance{"two", "zone"});
} }
std::string status_to_string(int8_t status) std::string status_to_string(int8_t status)
@ -89,7 +107,7 @@ private:
std::shared_ptr<plansys2::PlannerClient> planner_client_; std::shared_ptr<plansys2::PlannerClient> planner_client_;
}; };
int main(int argc, char** argv) int main(int argc, char **argv)
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
auto node = std::make_shared<RasmsController>(); auto node = std::make_shared<RasmsController>();

View file

@ -1,17 +1,3 @@
// Copyright 2019 Intelligent Robotics Lab
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <memory> #include <memory>
#include <random> #include <random>
@ -25,13 +11,11 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp_action/rclcpp_action.hpp"
class DummyController : public rclcpp::Node class RasmsController: public rclcpp::Node
{ {
public: public:
DummyController() RasmsController(): rclcpp::Node("rasms_controller")
: rclcpp::Node("dummy_controller") {}
{
}
void init() void init()
{ {
@ -52,19 +36,17 @@ public:
{ {
RCLCPP_ERROR(get_logger(), "Error starting a new plan (first)"); RCLCPP_ERROR(get_logger(), "Error starting a new plan (first)");
} }
} } else {
else
{
RCLCPP_ERROR_STREAM( RCLCPP_ERROR_STREAM(
this->get_logger(), "Could not find plan to reach goal " << parser::pddl::toString(problem_expert_->getGoal())); this->get_logger(), "Could not find plan to reach goal " <<
parser::pddl::toString(problem_expert_->getGoal()));
} }
} }
void init_knowledge() void init_knowledge()
{ {
problem_expert_->addInstance(plansys2::Instance{"rasms", "robot"}); problem_expert_->addInstance(plansys2::Instance{"rasms", "robot"});
problem_expert_->addInstance(plansys2::Instance{"zone", "zone"}); problem_expert_->setGoal(plansys2::Goal("robot moved"));
problem_expert_->setGoal(plansys2::Goal("(and(robot_moved rasms zone))"));
} }
std::string status_to_string(int8_t status) std::string status_to_string(int8_t status)
@ -107,10 +89,10 @@ private:
std::shared_ptr<plansys2::PlannerClient> planner_client_; std::shared_ptr<plansys2::PlannerClient> planner_client_;
}; };
int main(int argc, char **argv) int main(int argc, char** argv)
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
auto node = std::make_shared<DummyController>(); auto node = std::make_shared<RasmsController>();
node->init(); node->init();