plansys2: initialize move group interface
This commit is contained in:
parent
8ac7ee77df
commit
dffd9816bd
25 changed files with 1152 additions and 36 deletions
21
.vscode/c_cpp_properties.json
vendored
Normal file
21
.vscode/c_cpp_properties.json
vendored
Normal 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
|
||||||
|
}
|
8
.vscode/settings.json
vendored
Normal file
8
.vscode/settings.json
vendored
Normal file
|
@ -0,0 +1,8 @@
|
||||||
|
{
|
||||||
|
"python.autoComplete.extraPaths": [
|
||||||
|
"/opt/ros/foxy/lib/python3.8/site-packages"
|
||||||
|
],
|
||||||
|
"python.analysis.extraPaths": [
|
||||||
|
"/opt/ros/foxy/lib/python3.8/site-packages"
|
||||||
|
]
|
||||||
|
}
|
21
rasms_description/.vscode/c_cpp_properties.json
vendored
Normal file
21
rasms_description/.vscode/c_cpp_properties.json
vendored
Normal 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
|
||||||
|
}
|
5
rasms_description/.vscode/settings.json
vendored
Normal file
5
rasms_description/.vscode/settings.json
vendored
Normal file
|
@ -0,0 +1,5 @@
|
||||||
|
{
|
||||||
|
"python.autoComplete.extraPaths": [
|
||||||
|
"/opt/ros/foxy/lib/python3.8/site-packages"
|
||||||
|
]
|
||||||
|
}
|
81
rasms_manipulator/CMakeLists.txt
Normal file
81
rasms_manipulator/CMakeLists.txt
Normal file
|
@ -0,0 +1,81 @@
|
||||||
|
cmake_minimum_required(VERSION 3.5)
|
||||||
|
project(rasms_manipulator)
|
||||||
|
|
||||||
|
find_package(ament_cmake REQUIRED)
|
||||||
|
find_package(rclcpp REQUIRED)
|
||||||
|
find_package(rclcpp_action REQUIRED)
|
||||||
|
find_package(geometry_msgs REQUIRED)
|
||||||
|
find_package(tf2_geometry_msgs REQUIRED)
|
||||||
|
find_package(moveit_msgs REQUIRED)
|
||||||
|
find_package(moveit_core REQUIRED)
|
||||||
|
find_package(moveit_ros_planning REQUIRED)
|
||||||
|
find_package(moveit_ros_planning_interface REQUIRED)
|
||||||
|
find_package(plansys2_msgs REQUIRED)
|
||||||
|
find_package(plansys2_domain_expert REQUIRED)
|
||||||
|
find_package(plansys2_executor REQUIRED)
|
||||||
|
find_package(plansys2_planner REQUIRED)
|
||||||
|
find_package(plansys2_problem_expert REQUIRED)
|
||||||
|
find_package(plansys2_pddl_parser REQUIRED)
|
||||||
|
find_package(ament_index_cpp REQUIRED) #wtf?
|
||||||
|
find_package(plansys2_bt_actions REQUIRED)
|
||||||
|
|
||||||
|
if (NOT CMAKE_CXX_STANDARD)
|
||||||
|
set(CMAKE_CXX_STANDARD 17)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
set(dependencies
|
||||||
|
rclcpp
|
||||||
|
rclcpp_action
|
||||||
|
geometry_msgs
|
||||||
|
tf2_geometry_msgs
|
||||||
|
moveit_msgs
|
||||||
|
moveit_core
|
||||||
|
moveit_ros_planning
|
||||||
|
moveit_ros_planning_interface
|
||||||
|
plansys2_msgs
|
||||||
|
plansys2_domain_expert
|
||||||
|
plansys2_executor
|
||||||
|
plansys2_planner
|
||||||
|
plansys2_problem_expert
|
||||||
|
plansys2_pddl_parser
|
||||||
|
ament_index_cpp
|
||||||
|
plansys2_bt_actions
|
||||||
|
)
|
||||||
|
|
||||||
|
include_directories(include)
|
||||||
|
|
||||||
|
add_library(plansys2_move_bt_node SHARED src/behavior_tree_nodes/Move.cpp)
|
||||||
|
list(APPEND plugin_libs plansys2_move_bt_node)
|
||||||
|
|
||||||
|
foreach(bt_plugin ${plugin_libs})
|
||||||
|
ament_target_dependencies(${bt_plugin} ${dependencies})
|
||||||
|
target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT)
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
add_executable(assemble_action_node src/assemble_action_node.cpp)
|
||||||
|
ament_target_dependencies(assemble_action_node ${dependencies})
|
||||||
|
|
||||||
|
add_executable(assemble_controller_node src/assemble_controller_node.cpp)
|
||||||
|
ament_target_dependencies(assemble_controller_node ${dependencies})
|
||||||
|
|
||||||
|
install(DIRECTORY launch pddl behavior_trees_xml config DESTINATION share/${PROJECT_NAME})
|
||||||
|
|
||||||
|
install(TARGETS
|
||||||
|
assemble_action_node
|
||||||
|
assemble_controller_node
|
||||||
|
${plugin_libs}
|
||||||
|
ARCHIVE DESTINATION lib
|
||||||
|
LIBRARY DESTINATION lib
|
||||||
|
RUNTIME DESTINATION lib/${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
|
||||||
|
if(BUILD_TESTING)
|
||||||
|
find_package(ament_lint_auto REQUIRED)
|
||||||
|
ament_lint_auto_find_test_dependencies()
|
||||||
|
|
||||||
|
find_package(ament_cmake_gtest REQUIRED)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
ament_export_dependencies(${dependencies})
|
||||||
|
|
||||||
|
ament_package()
|
|
@ -1,7 +1,7 @@
|
||||||
<root main_tree_to_execute = "MainTree" >
|
<root main_tree_to_execute = "MainTree" >
|
||||||
<BehaviorTree ID="MainTree">
|
<BehaviorTree ID="MainTree">
|
||||||
<Sequence name="assemble">
|
<Sequence name="Move">
|
||||||
<Move name="move" goal="${pose}"/>
|
<Move name="move" goal="${arg2}"/>
|
||||||
</Sequence>
|
</Sequence>
|
||||||
</BehaviorTree>
|
</BehaviorTree>
|
||||||
</root>
|
</root>
|
|
@ -4,5 +4,5 @@ move_1:
|
||||||
- plansys2_move_bt_node
|
- plansys2_move_bt_node
|
||||||
waypoints: ["zero"]
|
waypoints: ["zero"]
|
||||||
waypoints_coords:
|
waypoints_coords:
|
||||||
zero: [0.0, -2.0, 0.0, 0.0]
|
zero: [0.0, -2.0, 0.0]
|
||||||
|
|
|
@ -5,8 +5,6 @@
|
||||||
|
|
||||||
#include "rclcpp/rclcpp.hpp"
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
|
||||||
#include "geometry_msgs/msg/pose2_d.hpp"
|
|
||||||
|
|
||||||
#include "plansys2_bt_actions/BTActionNode.hpp"
|
#include "plansys2_bt_actions/BTActionNode.hpp"
|
||||||
#include "behaviortree_cpp_v3/behavior_tree.h"
|
#include "behaviortree_cpp_v3/behavior_tree.h"
|
||||||
#include "behaviortree_cpp_v3/bt_factory.h"
|
#include "behaviortree_cpp_v3/bt_factory.h"
|
||||||
|
@ -14,15 +12,14 @@
|
||||||
#include "moveit_msgs/msg/place_location.hpp"
|
#include "moveit_msgs/msg/place_location.hpp"
|
||||||
#include "moveit_msgs/msg/move_it_error_codes.hpp"
|
#include "moveit_msgs/msg/move_it_error_codes.hpp"
|
||||||
#include "moveit_msgs/action/move_group.hpp"
|
#include "moveit_msgs/action/move_group.hpp"
|
||||||
#include "moveit_msgs/action/"
|
|
||||||
|
|
||||||
#include <moveit/moveit_cpp/moveit_cpp.h>
|
#include "moveit/moveit_cpp/moveit_cpp.h"
|
||||||
|
|
||||||
#include <geometry_msgs/msg/point_stamped.h>
|
#include "geometry_msgs/msg/point_stamped.h"
|
||||||
|
|
||||||
namespace rasms_manipulation
|
namespace rasms_manipulation
|
||||||
{
|
{
|
||||||
class Move: public plansys2::BtActionNode<moveit_msgs::MoveGroupAction>
|
class Move: public plansys2::BtActionNode<moveit_msgs::action::MoveGroup>
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
explicit Move(
|
explicit Move(
|
||||||
|
|
|
@ -22,6 +22,16 @@ def generate_launch_description():
|
||||||
stdout_linebuf_envvar = SetEnvironmentVariable(
|
stdout_linebuf_envvar = SetEnvironmentVariable(
|
||||||
'RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1')
|
'RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1')
|
||||||
|
|
||||||
|
plansys2_cmd = IncludeLaunchDescription(
|
||||||
|
PythonLaunchDescriptionSource(os.path.join(
|
||||||
|
get_package_share_directory('plansys2_bringup'),
|
||||||
|
'launch',
|
||||||
|
'plansys2_bringup_launch_monolithic.py')),
|
||||||
|
launch_arguments={
|
||||||
|
'model_file': pkg_dir + '/pddl/domain.pddl',
|
||||||
|
'namespace': namespace
|
||||||
|
}.items())
|
||||||
|
|
||||||
move_1 = Node(
|
move_1 = Node(
|
||||||
package='plansys2_bt_actions',
|
package='plansys2_bt_actions',
|
||||||
executable='bt_action_node',
|
executable='bt_action_node',
|
||||||
|
@ -32,6 +42,8 @@ def generate_launch_description():
|
||||||
pkg_dir + '/config/params.yaml',
|
pkg_dir + '/config/params.yaml',
|
||||||
{
|
{
|
||||||
'action_name': 'move',
|
'action_name': 'move',
|
||||||
|
'publisher_port': 1668,
|
||||||
|
'server_port': 1669,
|
||||||
'bt_xml_file': pkg_dir + '/behavior_trees_xml/move.xml'
|
'bt_xml_file': pkg_dir + '/behavior_trees_xml/move.xml'
|
||||||
}
|
}
|
||||||
])
|
])
|
||||||
|
@ -40,8 +52,9 @@ def generate_launch_description():
|
||||||
|
|
||||||
ld.add_action(stdout_linebuf_envvar)
|
ld.add_action(stdout_linebuf_envvar)
|
||||||
ld.add_action(declare_namespace_cmd)
|
ld.add_action(declare_namespace_cmd)
|
||||||
|
|
||||||
# Declare the launch options
|
# Declare the launch options
|
||||||
|
ld.add_action(plansys2_cmd)
|
||||||
ld.add_action(move_1)
|
ld.add_action(move_1)
|
||||||
|
|
||||||
return ld
|
return ld
|
38
rasms_manipulator/package.xml
Normal file
38
rasms_manipulator/package.xml
Normal file
|
@ -0,0 +1,38 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xds" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
|
||||||
|
<package format="3">
|
||||||
|
<name>rasms_manipulator</name>
|
||||||
|
<version>0.0.1</version>
|
||||||
|
|
||||||
|
<description>A simple of ROS2 Planning System</description>
|
||||||
|
<maintainer email="fmrico@gmail.com">Francisco Martin Rico</maintainer>
|
||||||
|
|
||||||
|
<license>Apache License, Version 2.0</license>
|
||||||
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<depend>rclcpp</depend>
|
||||||
|
<depend>rclcpp_action</depend>
|
||||||
|
<depend>geometry_msgs</depend>
|
||||||
|
<depend>tf2_geometry_msgs</depend>
|
||||||
|
<depend>moveit_msgs</depend>
|
||||||
|
<depend>moveit_core</depend>
|
||||||
|
<depend>moveit_ros_planning</depend>
|
||||||
|
<depend>moveit_ros_planning_interface</depend>
|
||||||
|
<depend>plansys2_msgs</depend>
|
||||||
|
<depend>plansys2_domain_expert</depend>
|
||||||
|
<depend>plansys2_executor</depend>
|
||||||
|
<depend>plansys2_planner</depend>
|
||||||
|
<depend>plansys2_problem_expert</depend>
|
||||||
|
<depend>plansys2_pddl_parser</depend>
|
||||||
|
<depend>ament_index_cpp</depend>
|
||||||
|
<depend>plansys2_bt_actions</depend>
|
||||||
|
|
||||||
|
<test_depend>ament_lint_common</test_depend>
|
||||||
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
<test_depend>ament_cmake_gtest</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
7
rasms_manipulator/pddl/commands
Normal file
7
rasms_manipulator/pddl/commands
Normal file
|
@ -0,0 +1,7 @@
|
||||||
|
set instance rasms robot
|
||||||
|
|
||||||
|
set instance assembly_zone zone
|
||||||
|
|
||||||
|
set predicate (robot_at rasms assembly_zone)
|
||||||
|
|
||||||
|
set goal (and())
|
35
rasms_manipulator/pddl/domain.pddl
Normal file
35
rasms_manipulator/pddl/domain.pddl
Normal file
|
@ -0,0 +1,35 @@
|
||||||
|
(define (domain rasms)
|
||||||
|
(:requirements :strips :typing :adl :fluents :durative-actions :typing)
|
||||||
|
|
||||||
|
;; Types ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||||
|
(:types
|
||||||
|
robot
|
||||||
|
zone
|
||||||
|
);; end Types ;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||||
|
|
||||||
|
;; Predicates ;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||||
|
(:predicates
|
||||||
|
|
||||||
|
(robot_at ?r - robot ?z - zone)
|
||||||
|
(robot_moved ?r - robot ?z - zone)
|
||||||
|
|
||||||
|
);; end Predicates ;;;;;;;;;;;;;;;;;;;;
|
||||||
|
|
||||||
|
;; Functions ;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||||
|
(:functions
|
||||||
|
|
||||||
|
);; end Functions ;;;;;;;;;;;;;;;;;;;;
|
||||||
|
|
||||||
|
;; Actions ;;;;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||||
|
(:durative-action move
|
||||||
|
:parameters (?r - robot ?z - zone)
|
||||||
|
:duration ( = ?duration 5)
|
||||||
|
:condition (and
|
||||||
|
(over all(robot_at ?r ?z))
|
||||||
|
)
|
||||||
|
:effect (and
|
||||||
|
(at end(robot_moved ?r ?z))
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
);; end Domain ;;;;;;;;;;;;;;;;;;;;;;;;
|
|
@ -65,8 +65,8 @@ public:
|
||||||
|
|
||||||
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_->setGoal(plansys2::Goal("robot moved"));
|
||||||
}
|
}
|
||||||
|
|
||||||
void step()
|
void step()
|
||||||
|
|
|
@ -3,17 +3,13 @@
|
||||||
|
|
||||||
#include "rasms_bt/behavior_tree_nodes/Move.hpp"
|
#include "rasms_bt/behavior_tree_nodes/Move.hpp"
|
||||||
|
|
||||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
|
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
|
||||||
|
#include "moveit/move_group_interface/move_group_interface.h"
|
||||||
|
#include "moveit/planning_scene_interface/planning_scene_interface.h"
|
||||||
|
|
||||||
#include <moveit/moveit_cpp/moveit_cpp.h>
|
#include "geometry_msgs/msg/pose_stamped.h"
|
||||||
#include <moveit/moveit_cpp/planning_component.h>
|
|
||||||
#include <moveit/move_group_interface/move_group_interface.h>
|
|
||||||
|
|
||||||
#include <geometry_msgs/msg/point_stamped.h>
|
#include "rclcpp_lifecycle/lifecycle_node.hpp"
|
||||||
#include <geometry_msgs/msg/pose.h>
|
|
||||||
|
|
||||||
#include <behaviortree_cpp_v3/behavior_tree.h>
|
|
||||||
#include <rclcpp_lifecycle/lifecycle_node.hpp>
|
|
||||||
|
|
||||||
namespace rasms_manipulation
|
namespace rasms_manipulation
|
||||||
{
|
{
|
||||||
|
@ -21,7 +17,7 @@ Move::Move(
|
||||||
const std::string& xml_tag_name,
|
const std::string& xml_tag_name,
|
||||||
const std::string& action_name,
|
const std::string& action_name,
|
||||||
const BT::NodeConfiguration& conf)
|
const BT::NodeConfiguration& conf)
|
||||||
: plansys::BtActionNode<moveit_msgs::MoveGroupAction>(xml_tag_name, action_name, conf)
|
: plansys2::BtActionNode<moveit_msgs::action::MoveGroup>(xml_tag_name, action_name, conf)
|
||||||
{
|
{
|
||||||
rclcpp::Node::SharedPtr node;
|
rclcpp::Node::SharedPtr node;
|
||||||
config().blackboard->get("node", node);
|
config().blackboard->get("node", node);
|
||||||
|
@ -56,7 +52,6 @@ Move::Move(
|
||||||
pose.position.x = coords[0];
|
pose.position.x = coords[0];
|
||||||
pose.position.y = coords[1];
|
pose.position.y = coords[1];
|
||||||
pose.position.z = coords[2];
|
pose.position.z = coords[2];
|
||||||
pose.position.w = coords[3]
|
|
||||||
// pose.orientation.x = coords[3];
|
// pose.orientation.x = coords[3];
|
||||||
// pose.orientation.y = coords[4];
|
// pose.orientation.y = coords[4];
|
||||||
// pose.orientation.z = coords[5];
|
// pose.orientation.z = coords[5];
|
||||||
|
@ -72,9 +67,7 @@ Move::Move(
|
||||||
|
|
||||||
void Move::on_tick()
|
void Move::on_tick()
|
||||||
{
|
{
|
||||||
rclcpp::NodeOptions node_options;
|
rclcpp::Node::SharedPtr node;
|
||||||
node_options.automatically_declare_parameters_from_overrides(true);
|
|
||||||
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("moveit_cpp_move", node_options);
|
|
||||||
config().blackboard->get("node", node);
|
config().blackboard->get("node", node);
|
||||||
|
|
||||||
|
|
||||||
|
@ -88,23 +81,28 @@ void Move::on_tick()
|
||||||
std::cerr << "No coordinate for waypoint [" << goal << "]" << std::endl;
|
std::cerr << "No coordinate for waypoint [" << goal << "]" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
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(PLANNING_GROUP);
|
//move_group->setStartState(*move_group->getCurrentState());
|
||||||
|
|
||||||
|
/*----------
|
||||||
|
00823 // pose goal;
|
||||||
|
00824 // for each link we have a set of possible goal locations;
|
||||||
|
00825 std::map<std::string, std::vector<geometry_msgs::PoseStamped> > pose_targets_;
|
||||||
|
----------*/
|
||||||
geometry_msgs::msg::PoseStamped goal_pos;
|
geometry_msgs::msg::PoseStamped goal_pos;
|
||||||
|
|
||||||
goal_pos.header.frame_id = "base";
|
goal_pos.header.frame_id = "base";
|
||||||
goal_pos.pose.position.x = pose2moveit.position.x;
|
goal_pos.pose.position.x = pose2moveit.position.x;
|
||||||
goal_pos.pose.position.y = pose2moveit.position.y;
|
goal_pos.pose.position.y = pose2moveit.position.y;
|
||||||
goal_pos.pose.position.z = pose2moveit.position.z;
|
goal_pos.pose.position.z = pose2moveit.position.z;
|
||||||
goal_pos.pose.position.w = pose2moveit.position.w
|
|
||||||
// goal_pos.pose.orientation = pose2moveit.orientation;
|
// goal_pos.pose.orientation = pose2moveit.orientation;
|
||||||
|
|
||||||
move_group.setPoseTarget(goal_pose, "link6");
|
move_group.setPoseTarget(goal_pos, "link6");
|
||||||
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
|
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
|
||||||
moveit::planning_interface::MoveItErrorCode success = move_group(my_plan);
|
bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
|
||||||
if (success)
|
if (success)
|
||||||
{
|
{
|
||||||
|
//move_group->setStartStateToCurrentState();
|
||||||
move_group.execute(my_plan);
|
move_group.execute(my_plan);
|
||||||
move_group.move();
|
move_group.move();
|
||||||
} else {
|
} else {
|
||||||
|
@ -119,7 +117,7 @@ Move::on_success()
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
} // namespace plansys2_bt_tests
|
} // namespace plansys222_bt_tests
|
||||||
|
|
||||||
#include "behaviortree_cpp_v3/bt_factory.h"
|
#include "behaviortree_cpp_v3/bt_factory.h"
|
||||||
BT_REGISTER_NODES(factory)
|
BT_REGISTER_NODES(factory)
|
||||||
|
|
21
rasms_moveit_config/config/.vscode/c_cpp_properties.json
vendored
Normal file
21
rasms_moveit_config/config/.vscode/c_cpp_properties.json
vendored
Normal 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
|
||||||
|
}
|
5
rasms_moveit_config/config/.vscode/settings.json
vendored
Normal file
5
rasms_moveit_config/config/.vscode/settings.json
vendored
Normal file
|
@ -0,0 +1,5 @@
|
||||||
|
{
|
||||||
|
"python.autoComplete.extraPaths": [
|
||||||
|
"/opt/ros/foxy/lib/python3.8/site-packages"
|
||||||
|
]
|
||||||
|
}
|
35
rasms_moveit_config/config/joint_limits.yml
Normal file
35
rasms_moveit_config/config/joint_limits.yml
Normal file
|
@ -0,0 +1,35 @@
|
||||||
|
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
|
||||||
|
|
||||||
|
# For beginners, we downscale velocity and acceleration limits.
|
||||||
|
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
|
||||||
|
default_velocity_scaling_factor: 0.1
|
||||||
|
default_acceleration_scaling_factor: 0.1
|
||||||
|
|
||||||
|
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
|
||||||
|
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
|
||||||
|
joint_limits:
|
||||||
|
joint1:
|
||||||
|
has_velocity_limits: false
|
||||||
|
max_velocity: 0
|
||||||
|
has_acceleration_limits: false
|
||||||
|
max_acceleration: 0
|
||||||
|
joint3:
|
||||||
|
has_velocity_limits: false
|
||||||
|
max_velocity: 0
|
||||||
|
has_acceleration_limits: false
|
||||||
|
max_acceleration: 0
|
||||||
|
joint4:
|
||||||
|
has_velocity_limits: false
|
||||||
|
max_velocity: 0
|
||||||
|
has_acceleration_limits: false
|
||||||
|
max_acceleration: 0
|
||||||
|
joint5:
|
||||||
|
has_velocity_limits: false
|
||||||
|
max_velocity: 0
|
||||||
|
has_acceleration_limits: false
|
||||||
|
max_acceleration: 0
|
||||||
|
joint6:
|
||||||
|
has_velocity_limits: false
|
||||||
|
max_velocity: 0
|
||||||
|
has_acceleration_limits: false
|
||||||
|
max_acceleration: 0
|
4
rasms_moveit_config/config/kinematics.yml
Normal file
4
rasms_moveit_config/config/kinematics.yml
Normal file
|
@ -0,0 +1,4 @@
|
||||||
|
rasms_arm_group:
|
||||||
|
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
|
||||||
|
kinematics_solver_search_resolution: 0.005
|
||||||
|
kinematics_solver_timeout: 0.05
|
20
rasms_moveit_config/config/moveit_cpp.yml
Normal file
20
rasms_moveit_config/config/moveit_cpp.yml
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
rasms_moveit:
|
||||||
|
ros__parameters:
|
||||||
|
planning_scene_monitor_options:
|
||||||
|
name: "planning_scene_monitor"
|
||||||
|
robot_description: "robot_description"
|
||||||
|
joint_state_topic: "/joint_states"
|
||||||
|
attached_collision_object_topic: "/planning_scene_monitor"
|
||||||
|
publish_planning_scene_topic: "/publish_planning_scene"
|
||||||
|
monitored_planning_scene_topic: "/monitored_planning_scene"
|
||||||
|
wait_for_initial_state_timeout: 10.0
|
||||||
|
|
||||||
|
planning_pipelines:
|
||||||
|
#namespace: "moveit_cpp" # optional, default is ~
|
||||||
|
pipeline_names: ["ompl"]
|
||||||
|
|
||||||
|
plan_request_params:
|
||||||
|
planning_attempts: 10
|
||||||
|
planning_pipeline: ompl
|
||||||
|
max_velocity_scaling_factor: 1.0
|
||||||
|
max_acceleration_scaling_factor: 1.0
|
151
rasms_moveit_config/config/ompl_planning.yml
Normal file
151
rasms_moveit_config/config/ompl_planning.yml
Normal file
|
@ -0,0 +1,151 @@
|
||||||
|
planner_configs:
|
||||||
|
SBLkConfigDefault:
|
||||||
|
type: geometric::SBL
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
ESTkConfigDefault:
|
||||||
|
type: geometric::EST
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
|
||||||
|
LBKPIECEkConfigDefault:
|
||||||
|
type: geometric::LBKPIECE
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
|
||||||
|
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
|
||||||
|
BKPIECEkConfigDefault:
|
||||||
|
type: geometric::BKPIECE
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
|
||||||
|
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
|
||||||
|
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
|
||||||
|
KPIECEkConfigDefault:
|
||||||
|
type: geometric::KPIECE
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
|
||||||
|
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
|
||||||
|
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
|
||||||
|
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
|
||||||
|
RRTkConfigDefault:
|
||||||
|
type: geometric::RRT
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
|
||||||
|
RRTConnectkConfigDefault:
|
||||||
|
type: geometric::RRTConnect
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
RRTstarkConfigDefault:
|
||||||
|
type: geometric::RRTstar
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
|
||||||
|
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
|
||||||
|
TRRTkConfigDefault:
|
||||||
|
type: geometric::TRRT
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
|
||||||
|
max_states_failed: 10 # when to start increasing temp. default: 10
|
||||||
|
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
|
||||||
|
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
|
||||||
|
init_temperature: 10e-6 # initial temperature. default: 10e-6
|
||||||
|
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
|
||||||
|
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
|
||||||
|
k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
|
||||||
|
PRMkConfigDefault:
|
||||||
|
type: geometric::PRM
|
||||||
|
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
|
||||||
|
PRMstarkConfigDefault:
|
||||||
|
type: geometric::PRMstar
|
||||||
|
FMTkConfigDefault:
|
||||||
|
type: geometric::FMT
|
||||||
|
num_samples: 1000 # number of states that the planner should sample. default: 1000
|
||||||
|
radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
|
||||||
|
nearest_k: 1 # use Knearest strategy. default: 1
|
||||||
|
cache_cc: 1 # use collision checking cache. default: 1
|
||||||
|
heuristics: 0 # activate cost to go heuristics. default: 0
|
||||||
|
extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
|
||||||
|
BFMTkConfigDefault:
|
||||||
|
type: geometric::BFMT
|
||||||
|
num_samples: 1000 # number of states that the planner should sample. default: 1000
|
||||||
|
radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
|
||||||
|
nearest_k: 1 # use the Knearest strategy. default: 1
|
||||||
|
balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
|
||||||
|
optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
|
||||||
|
heuristics: 1 # activates cost to go heuristics. default: 1
|
||||||
|
cache_cc: 1 # use the collision checking cache. default: 1
|
||||||
|
extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
|
||||||
|
PDSTkConfigDefault:
|
||||||
|
type: geometric::PDST
|
||||||
|
STRIDEkConfigDefault:
|
||||||
|
type: geometric::STRIDE
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
|
||||||
|
use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
|
||||||
|
degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
|
||||||
|
max_degree: 18 # max degree of a node in the GNAT. default: 12
|
||||||
|
min_degree: 12 # min degree of a node in the GNAT. default: 12
|
||||||
|
max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
|
||||||
|
estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
|
||||||
|
min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
|
||||||
|
BiTRRTkConfigDefault:
|
||||||
|
type: geometric::BiTRRT
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
|
||||||
|
init_temperature: 100 # initial temperature. default: 100
|
||||||
|
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
|
||||||
|
frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
|
||||||
|
cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
|
||||||
|
LBTRRTkConfigDefault:
|
||||||
|
type: geometric::LBTRRT
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
|
||||||
|
epsilon: 0.4 # optimality approximation factor. default: 0.4
|
||||||
|
BiESTkConfigDefault:
|
||||||
|
type: geometric::BiEST
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
ProjESTkConfigDefault:
|
||||||
|
type: geometric::ProjEST
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
|
||||||
|
LazyPRMkConfigDefault:
|
||||||
|
type: geometric::LazyPRM
|
||||||
|
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
|
||||||
|
LazyPRMstarkConfigDefault:
|
||||||
|
type: geometric::LazyPRMstar
|
||||||
|
SPARSkConfigDefault:
|
||||||
|
type: geometric::SPARS
|
||||||
|
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
|
||||||
|
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
|
||||||
|
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
|
||||||
|
max_failures: 1000 # maximum consecutive failure limit. default: 1000
|
||||||
|
SPARStwokConfigDefault:
|
||||||
|
type: geometric::SPARStwo
|
||||||
|
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
|
||||||
|
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
|
||||||
|
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
|
||||||
|
max_failures: 5000 # maximum consecutive failure limit. default: 5000
|
||||||
|
TrajOptDefault:
|
||||||
|
type: geometric::TrajOpt
|
||||||
|
|
||||||
|
rasms_arm_group:
|
||||||
|
planner_configs:
|
||||||
|
- SBLkConfigDefault
|
||||||
|
- ESTkConfigDefault
|
||||||
|
- LBKPIECEkConfigDefault
|
||||||
|
- BKPIECEkConfigDefault
|
||||||
|
- KPIECEkConfigDefault
|
||||||
|
- RRTkConfigDefault
|
||||||
|
- RRTConnectkConfigDefault
|
||||||
|
- RRTstarkConfigDefault
|
||||||
|
- TRRTkConfigDefault
|
||||||
|
- PRMkConfigDefault
|
||||||
|
- PRMstarkConfigDefault
|
||||||
|
- FMTkConfigDefault
|
||||||
|
- BFMTkConfigDefault
|
||||||
|
- PDSTkConfigDefault
|
||||||
|
- STRIDEkConfigDefault
|
||||||
|
- BiTRRTkConfigDefault
|
||||||
|
- LBTRRTkConfigDefault
|
||||||
|
- BiESTkConfigDefault
|
||||||
|
- ProjESTkConfigDefault
|
||||||
|
- LazyPRMkConfigDefault
|
||||||
|
- LazyPRMstarkConfigDefault
|
||||||
|
- SPARSkConfigDefault
|
||||||
|
- SPARStwokConfigDefault
|
||||||
|
- TrajOptDefault
|
431
rasms_moveit_config/config/rasms.rviz
Normal file
431
rasms_moveit_config/config/rasms.rviz
Normal file
|
@ -0,0 +1,431 @@
|
||||||
|
Panels:
|
||||||
|
- Class: rviz_common/Displays
|
||||||
|
Help Height: 78
|
||||||
|
Name: Displays
|
||||||
|
Property Tree Widget:
|
||||||
|
Expanded:
|
||||||
|
- /Global Options1
|
||||||
|
- /Status1
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
Tree Height: 197
|
||||||
|
- Class: rviz_common/Selection
|
||||||
|
Name: Selection
|
||||||
|
- Class: rviz_common/Tool Properties
|
||||||
|
Expanded:
|
||||||
|
- /2D Goal Pose1
|
||||||
|
- /Publish Point1
|
||||||
|
Name: Tool Properties
|
||||||
|
Splitter Ratio: 0.5886790156364441
|
||||||
|
- Class: rviz_common/Views
|
||||||
|
Expanded:
|
||||||
|
- /Current View1
|
||||||
|
Name: Views
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
- Class: rviz_visual_tools/RvizVisualToolsGui
|
||||||
|
Name: RvizVisualToolsGui
|
||||||
|
Visualization Manager:
|
||||||
|
Class: ""
|
||||||
|
Displays:
|
||||||
|
- Alpha: 0.5
|
||||||
|
Cell Size: 1
|
||||||
|
Class: rviz_default_plugins/Grid
|
||||||
|
Color: 160; 160; 164
|
||||||
|
Enabled: true
|
||||||
|
Line Style:
|
||||||
|
Line Width: 0.029999999329447746
|
||||||
|
Value: Lines
|
||||||
|
Name: Grid
|
||||||
|
Normal Cell Count: 0
|
||||||
|
Offset:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Plane: XY
|
||||||
|
Plane Cell Count: 10
|
||||||
|
Reference Frame: <Fixed Frame>
|
||||||
|
Value: true
|
||||||
|
- Class: moveit_rviz_plugin/PlanningScene
|
||||||
|
Enabled: true
|
||||||
|
Move Group Namespace: ""
|
||||||
|
Name: PlanningScene
|
||||||
|
Planning Scene Topic: /monitored_planning_scene
|
||||||
|
Robot Description: robot_description
|
||||||
|
Scene Geometry:
|
||||||
|
Scene Alpha: 0.8999999761581421
|
||||||
|
Scene Color: 50; 230; 50
|
||||||
|
Scene Display Time: 0.20000000298023224
|
||||||
|
Show Scene Geometry: true
|
||||||
|
Voxel Coloring: Z-Axis
|
||||||
|
Voxel Rendering: Occupied Voxels
|
||||||
|
Scene Robot:
|
||||||
|
Attached Body Color: 150; 50; 150
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link1:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link2:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link3:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link4:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link5:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link6:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
world:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Robot Alpha: 1
|
||||||
|
Show Robot Collision: false
|
||||||
|
Show Robot Visual: true
|
||||||
|
Value: true
|
||||||
|
- Class: moveit_rviz_plugin/Trajectory
|
||||||
|
Color Enabled: false
|
||||||
|
Enabled: true
|
||||||
|
Interrupt Display: false
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link1:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link2:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link3:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link4:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link5:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link6:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
world:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Loop Animation: false
|
||||||
|
Name: Trajectory
|
||||||
|
Robo Alpha: 0.5
|
||||||
|
Robot Color: 150; 50; 150
|
||||||
|
Robot Description: robot_description
|
||||||
|
Show Robot Collision: false
|
||||||
|
Show Robot Visual: true
|
||||||
|
Show Trail: false
|
||||||
|
State Display Time: 0.05 s
|
||||||
|
Trail Step Size: 1
|
||||||
|
Trajectory Topic: /display_planned_path
|
||||||
|
Value: true
|
||||||
|
- Acceleration_Scaling_Factor: 0.1
|
||||||
|
Class: moveit_rviz_plugin/MotionPlanning
|
||||||
|
Enabled: true
|
||||||
|
Move Group Namespace: ""
|
||||||
|
MoveIt_Allow_Approximate_IK: false
|
||||||
|
MoveIt_Allow_External_Program: false
|
||||||
|
MoveIt_Allow_Replanning: false
|
||||||
|
MoveIt_Allow_Sensor_Positioning: false
|
||||||
|
MoveIt_Planning_Attempts: 10
|
||||||
|
MoveIt_Planning_Time: 5
|
||||||
|
MoveIt_Use_Cartesian_Path: false
|
||||||
|
MoveIt_Use_Constraint_Aware_IK: true
|
||||||
|
MoveIt_Warehouse_Host: 127.0.0.1
|
||||||
|
MoveIt_Warehouse_Port: 33829
|
||||||
|
MoveIt_Workspace:
|
||||||
|
Center:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Size:
|
||||||
|
X: 2
|
||||||
|
Y: 2
|
||||||
|
Z: 2
|
||||||
|
Name: MotionPlanning
|
||||||
|
Planned Path:
|
||||||
|
Color Enabled: false
|
||||||
|
Interrupt Display: false
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link1:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link2:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link3:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link4:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link5:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link6:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
world:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Loop Animation: false
|
||||||
|
Robot Alpha: 0.5
|
||||||
|
Robot Color: 150; 50; 150
|
||||||
|
Show Robot Collision: false
|
||||||
|
Show Robot Visual: true
|
||||||
|
Show Trail: false
|
||||||
|
State Display Time: 0.05 s
|
||||||
|
Trail Step Size: 1
|
||||||
|
Trajectory Topic: /move_group/display_planned_path
|
||||||
|
Planning Metrics:
|
||||||
|
Payload: 1
|
||||||
|
Show Joint Torques: false
|
||||||
|
Show Manipulability: false
|
||||||
|
Show Manipulability Index: false
|
||||||
|
Show Weight Limit: false
|
||||||
|
TextHeight: 0.07999999821186066
|
||||||
|
Planning Request:
|
||||||
|
Colliding Link Color: 255; 0; 0
|
||||||
|
Goal State Alpha: 1
|
||||||
|
Goal State Color: 250; 128; 0
|
||||||
|
Interactive Marker Size: 0
|
||||||
|
Joint Violation Color: 255; 0; 255
|
||||||
|
Planning Group: rasms_arm_group
|
||||||
|
Query Goal State: false
|
||||||
|
Query Start State: false
|
||||||
|
Show Workspace: false
|
||||||
|
Start State Alpha: 1
|
||||||
|
Start State Color: 0; 255; 0
|
||||||
|
Planning Scene Topic: /monitored_planning_scene
|
||||||
|
Robot Description: robot_description
|
||||||
|
Scene Geometry:
|
||||||
|
Scene Alpha: 0.8999999761581421
|
||||||
|
Scene Color: 50; 230; 50
|
||||||
|
Scene Display Time: 0.009999999776482582
|
||||||
|
Show Scene Geometry: true
|
||||||
|
Voxel Coloring: Z-Axis
|
||||||
|
Voxel Rendering: Occupied Voxels
|
||||||
|
Scene Robot:
|
||||||
|
Attached Body Color: 150; 50; 150
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link1:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link2:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link3:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link4:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link5:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link6:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
world:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Robot Alpha: 1
|
||||||
|
Show Robot Collision: false
|
||||||
|
Show Robot Visual: true
|
||||||
|
Value: true
|
||||||
|
Velocity_Scaling_Factor: 0.1
|
||||||
|
- Class: rviz_default_plugins/MarkerArray
|
||||||
|
Enabled: true
|
||||||
|
Name: MarkerArray
|
||||||
|
Namespaces:
|
||||||
|
{}
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /move_group_tutorial
|
||||||
|
Value: true
|
||||||
|
Enabled: true
|
||||||
|
Global Options:
|
||||||
|
Background Color: 48; 48; 48
|
||||||
|
Fixed Frame: base
|
||||||
|
Frame Rate: 30
|
||||||
|
Name: root
|
||||||
|
Tools:
|
||||||
|
- Class: rviz_default_plugins/Interact
|
||||||
|
Hide Inactive Objects: true
|
||||||
|
- Class: rviz_default_plugins/MoveCamera
|
||||||
|
- Class: rviz_default_plugins/Select
|
||||||
|
- Class: rviz_default_plugins/FocusCamera
|
||||||
|
- Class: rviz_default_plugins/Measure
|
||||||
|
Line color: 128; 128; 0
|
||||||
|
- Class: rviz_default_plugins/SetInitialPose
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /initialpose
|
||||||
|
- Class: rviz_default_plugins/SetGoal
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /goal_pose
|
||||||
|
- Class: rviz_default_plugins/PublishPoint
|
||||||
|
Single click: true
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /clicked_point
|
||||||
|
Transformation:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/TF
|
||||||
|
Value: true
|
||||||
|
Views:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/Orbit
|
||||||
|
Distance: 3.8008623123168945
|
||||||
|
Enable Stereo Rendering:
|
||||||
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
|
Stereo Focal Distance: 1
|
||||||
|
Swap Stereo Eyes: false
|
||||||
|
Value: false
|
||||||
|
Focal Point:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Focal Shape Fixed Size: true
|
||||||
|
Focal Shape Size: 0.05000000074505806
|
||||||
|
Invert Z Axis: false
|
||||||
|
Name: Current View
|
||||||
|
Near Clip Distance: 0.009999999776482582
|
||||||
|
Pitch: 0.72039794921875
|
||||||
|
Target Frame: <Fixed Frame>
|
||||||
|
Value: Orbit (rviz)
|
||||||
|
Yaw: 0.2953982949256897
|
||||||
|
Saved: ~
|
||||||
|
Window Geometry:
|
||||||
|
Displays:
|
||||||
|
collapsed: false
|
||||||
|
Height: 1043
|
||||||
|
Hide Left Dock: false
|
||||||
|
Hide Right Dock: false
|
||||||
|
MotionPlanning:
|
||||||
|
collapsed: false
|
||||||
|
MotionPlanning - Trajectory Slider:
|
||||||
|
collapsed: false
|
||||||
|
QMainWindow State: 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
|
||||||
|
RvizVisualToolsGui:
|
||||||
|
collapsed: false
|
||||||
|
Selection:
|
||||||
|
collapsed: false
|
||||||
|
Tool Properties:
|
||||||
|
collapsed: false
|
||||||
|
Trajectory - Trajectory Slider:
|
||||||
|
collapsed: false
|
||||||
|
Views:
|
||||||
|
collapsed: false
|
||||||
|
Width: 1920
|
||||||
|
X: 2560
|
||||||
|
Y: 360
|
26
rasms_moveit_config/config/rasms_controllers.yml
Normal file
26
rasms_moveit_config/config/rasms_controllers.yml
Normal file
|
@ -0,0 +1,26 @@
|
||||||
|
controller_manager:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 500 # Hz
|
||||||
|
|
||||||
|
joint_state_broadcaster:
|
||||||
|
type: joint_state_broadcaster/JointStateBroadcaster
|
||||||
|
|
||||||
|
rasms_arm_controller:
|
||||||
|
type: joint_trajectory_controller/JointTrajectoryController
|
||||||
|
|
||||||
|
rasms_arm_controller:
|
||||||
|
ros__parameters:
|
||||||
|
joints:
|
||||||
|
- joint1
|
||||||
|
- joint2
|
||||||
|
- joint3
|
||||||
|
- joint4
|
||||||
|
- joint5
|
||||||
|
- joint6
|
||||||
|
command_interfaces:
|
||||||
|
- position
|
||||||
|
state_interfaces:
|
||||||
|
- position
|
||||||
|
state_publish_rate: 50.0
|
||||||
|
action_monitor_rate: 20.0
|
||||||
|
|
16
rasms_moveit_config/config/rasms_moveit_controllers.yml
Normal file
16
rasms_moveit_config/config/rasms_moveit_controllers.yml
Normal file
|
@ -0,0 +1,16 @@
|
||||||
|
controller_names:
|
||||||
|
- rasms_arm_controller
|
||||||
|
|
||||||
|
# http://control.ros.org/ros2_controllers/joint_trajectory_controller/doc/userdoc.html#ros2-interface-of-the-controller
|
||||||
|
rasms_arm_controller:
|
||||||
|
action_ns: follow_joint_trajectory
|
||||||
|
type: FollowJointTrajectory
|
||||||
|
default: true
|
||||||
|
joints:
|
||||||
|
- joint1
|
||||||
|
- joint2
|
||||||
|
- joint3
|
||||||
|
- joint4
|
||||||
|
- joint5
|
||||||
|
- joint6
|
||||||
|
|
183
rasms_moveit_config/config/robasm_sgonov.rviz
Normal file
183
rasms_moveit_config/config/robasm_sgonov.rviz
Normal file
|
@ -0,0 +1,183 @@
|
||||||
|
Panels:
|
||||||
|
- Class: rviz_common/Displays
|
||||||
|
Help Height: 78
|
||||||
|
Name: Displays
|
||||||
|
Property Tree Widget:
|
||||||
|
Expanded:
|
||||||
|
- /Global Options1
|
||||||
|
- /Status1
|
||||||
|
- /RobotModel1
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
Tree Height: 787
|
||||||
|
- Class: rviz_common/Selection
|
||||||
|
Name: Selection
|
||||||
|
- Class: rviz_common/Tool Properties
|
||||||
|
Expanded:
|
||||||
|
- /2D Goal Pose1
|
||||||
|
- /Publish Point1
|
||||||
|
Name: Tool Properties
|
||||||
|
Splitter Ratio: 0.5886790156364441
|
||||||
|
- Class: rviz_common/Views
|
||||||
|
Expanded:
|
||||||
|
- /Current View1
|
||||||
|
Name: Views
|
||||||
|
Splitter Ratio: 0.5
|
||||||
|
Visualization Manager:
|
||||||
|
Class: ""
|
||||||
|
Displays:
|
||||||
|
- Alpha: 0.5
|
||||||
|
Cell Size: 1
|
||||||
|
Class: rviz_default_plugins/Grid
|
||||||
|
Color: 160; 160; 164
|
||||||
|
Enabled: true
|
||||||
|
Line Style:
|
||||||
|
Line Width: 0.029999999329447746
|
||||||
|
Value: Lines
|
||||||
|
Name: Grid
|
||||||
|
Normal Cell Count: 0
|
||||||
|
Offset:
|
||||||
|
X: 0
|
||||||
|
Y: 0
|
||||||
|
Z: 0
|
||||||
|
Plane: XY
|
||||||
|
Plane Cell Count: 10
|
||||||
|
Reference Frame: <Fixed Frame>
|
||||||
|
Value: true
|
||||||
|
- Alpha: 1
|
||||||
|
Class: rviz_default_plugins/RobotModel
|
||||||
|
Collision Enabled: false
|
||||||
|
Description File: ""
|
||||||
|
Description Source: Topic
|
||||||
|
Description Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /robot_description
|
||||||
|
Enabled: true
|
||||||
|
Links:
|
||||||
|
All Links Enabled: true
|
||||||
|
Expand Joint Details: false
|
||||||
|
Expand Link Details: false
|
||||||
|
Expand Tree: false
|
||||||
|
Link Tree Style: Links in Alphabetic Order
|
||||||
|
base:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link1:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link2:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link3:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link4:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link5:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
link6:
|
||||||
|
Alpha: 1
|
||||||
|
Show Axes: false
|
||||||
|
Show Trail: false
|
||||||
|
Value: true
|
||||||
|
Name: RobotModel
|
||||||
|
TF Prefix: ""
|
||||||
|
Update Interval: 0
|
||||||
|
Value: true
|
||||||
|
Visual Enabled: true
|
||||||
|
Enabled: true
|
||||||
|
Global Options:
|
||||||
|
Background Color: 48; 48; 48
|
||||||
|
Fixed Frame: base
|
||||||
|
Frame Rate: 30
|
||||||
|
Name: root
|
||||||
|
Tools:
|
||||||
|
- Class: rviz_default_plugins/Interact
|
||||||
|
Hide Inactive Objects: true
|
||||||
|
- Class: rviz_default_plugins/MoveCamera
|
||||||
|
- Class: rviz_default_plugins/Select
|
||||||
|
- Class: rviz_default_plugins/FocusCamera
|
||||||
|
- Class: rviz_default_plugins/Measure
|
||||||
|
Line color: 128; 128; 0
|
||||||
|
- Class: rviz_default_plugins/SetInitialPose
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /initialpose
|
||||||
|
- Class: rviz_default_plugins/SetGoal
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /goal_pose
|
||||||
|
- Class: rviz_default_plugins/PublishPoint
|
||||||
|
Single click: true
|
||||||
|
Topic:
|
||||||
|
Depth: 5
|
||||||
|
Durability Policy: Volatile
|
||||||
|
History Policy: Keep Last
|
||||||
|
Reliability Policy: Reliable
|
||||||
|
Value: /clicked_point
|
||||||
|
Transformation:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/TF
|
||||||
|
Value: true
|
||||||
|
Views:
|
||||||
|
Current:
|
||||||
|
Class: rviz_default_plugins/Orbit
|
||||||
|
Distance: 1.4318417310714722
|
||||||
|
Enable Stereo Rendering:
|
||||||
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
|
Stereo Focal Distance: 1
|
||||||
|
Swap Stereo Eyes: false
|
||||||
|
Value: false
|
||||||
|
Focal Point:
|
||||||
|
X: 0.01542382501065731
|
||||||
|
Y: -0.006365143693983555
|
||||||
|
Z: 0.15774454176425934
|
||||||
|
Focal Shape Fixed Size: true
|
||||||
|
Focal Shape Size: 0.05000000074505806
|
||||||
|
Invert Z Axis: false
|
||||||
|
Name:Current View
|
||||||
|
Near Clip Distance: 0.009999999776482582
|
||||||
|
Pitch: 0.5703980326652527
|
||||||
|
Target Frame: <Fixed Frame>
|
||||||
|
Value: Orbit (rviz)
|
||||||
|
Yaw: 0.5603898763656616
|
||||||
|
Saved: ~
|
||||||
|
Window Geometry:
|
||||||
|
Displays:
|
||||||
|
collapsed: false
|
||||||
|
Height: 1016
|
||||||
|
Hide Left Dock: false
|
||||||
|
Hide Right Dock: false
|
||||||
|
QMainWindow State: 000000ff00000000fd0000000400000000000001560000039efc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000039e000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000039efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000039e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004c70000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||||
|
Selection:
|
||||||
|
collapsed: false
|
||||||
|
Tool Properties:
|
||||||
|
collapsed: false
|
||||||
|
Views:
|
||||||
|
collapsed: false
|
||||||
|
Width: 1848
|
||||||
|
X: 72
|
||||||
|
Y: 27
|
||||||
|
|
|
@ -23,7 +23,7 @@ def generate_launch_description():
|
||||||
PathJoinSubstitution([
|
PathJoinSubstitution([
|
||||||
FindPackageShare("gazebo_ros"),
|
FindPackageShare("gazebo_ros"),
|
||||||
"launch",
|
"launch",
|
||||||
"gazebo.launch.py"
|
"gzserver.launch.py"
|
||||||
])
|
])
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue