commit
This commit is contained in:
parent
af973fe0ee
commit
3861ebfc8d
6 changed files with 53 additions and 6 deletions
3
rasms_manipulator/.vscode/settings.json
vendored
3
rasms_manipulator/.vscode/settings.json
vendored
|
@ -10,5 +10,6 @@
|
||||||
"/home/splinter1984/plansys_ws/install/ros2_knowledge_graph_msgs/lib/python3.8/site-packages",
|
"/home/splinter1984/plansys_ws/install/ros2_knowledge_graph_msgs/lib/python3.8/site-packages",
|
||||||
"/opt/ros/foxy/lib/python3.8/site-packages"
|
"/opt/ros/foxy/lib/python3.8/site-packages"
|
||||||
],
|
],
|
||||||
"ros.distro": "foxy"
|
"ros.distro": "foxy",
|
||||||
|
"C_Cpp.errorSquiggles": "Disabled"
|
||||||
}
|
}
|
|
@ -1,6 +1,6 @@
|
||||||
<root main_tree_to_execute = "MainTree" >
|
<root main_tree_to_execute = "MainTree" >
|
||||||
<BehaviorTree ID="MainTree">
|
<BehaviorTree ID="MainTree">
|
||||||
<Sequence name="root_sequence">
|
<Sequence name="move">
|
||||||
<Move name="move" goal="{pose}"/>
|
<Move name="move" goal="{pose}"/>
|
||||||
</Sequence>
|
</Sequence>
|
||||||
</BehaviorTree>
|
</BehaviorTree>
|
||||||
|
|
|
@ -1,7 +1,5 @@
|
||||||
move_1:
|
move:
|
||||||
ros_parameters:
|
ros_parameters:
|
||||||
plugins:
|
|
||||||
- rasms_move_bt_node
|
|
||||||
waypoints: ["zero", "one"]
|
waypoints: ["zero", "one"]
|
||||||
waypoints_coords:
|
waypoints_coords:
|
||||||
zero: [0.0, -2.0, 0.0]
|
zero: [0.0, -2.0, 0.0]
|
||||||
|
|
|
@ -13,6 +13,7 @@
|
||||||
|
|
||||||
#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 "tf2_geometry_msgs/tf2_geometry_msgs.h"
|
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
|
||||||
#include "tf2/transform_datatypes.h"
|
#include "tf2/transform_datatypes.h"
|
||||||
|
|
47
rasms_manipulator/launch/rasms_manipulation.launch.py
Normal file
47
rasms_manipulator/launch/rasms_manipulation.launch.py
Normal file
|
@ -0,0 +1,47 @@
|
||||||
|
import os
|
||||||
|
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable
|
||||||
|
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
|
||||||
|
pkg_dir = get_package_share_directory('rasms_manipulator')
|
||||||
|
namespace = LaunchConfiguration('namespace')
|
||||||
|
|
||||||
|
declare_namespace_cmd = DeclareLaunchArgument(
|
||||||
|
'namespace',
|
||||||
|
default_value='',
|
||||||
|
description='Namespace')
|
||||||
|
|
||||||
|
stdout_linebuf_envvar = SetEnvironmentVariable(
|
||||||
|
'RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1')
|
||||||
|
|
||||||
|
move_1 = Node(
|
||||||
|
package='plansys2_bt_actions',
|
||||||
|
executable='bt_action_node',
|
||||||
|
name='move_1',
|
||||||
|
namespace=namespace,
|
||||||
|
output='screen',
|
||||||
|
parameters=[
|
||||||
|
pkg_dir + '/config/params.yaml',
|
||||||
|
{
|
||||||
|
'action_name': 'move',
|
||||||
|
'bt_xml_file': pkg_dir + '/behavior_trees_xml/move.xml'
|
||||||
|
}
|
||||||
|
])
|
||||||
|
|
||||||
|
ld = LaunchDescription()
|
||||||
|
|
||||||
|
ld.add_action(stdout_linebuf_envvar)
|
||||||
|
ld.add_action(declare_namespace_cmd)
|
||||||
|
|
||||||
|
# Declare the launch options
|
||||||
|
ld.add_action(move_1)
|
||||||
|
|
||||||
|
return ld
|
|
@ -89,7 +89,7 @@ private:
|
||||||
std::shared_ptr<plansys2::PlannerClient> planner_client_;
|
std::shared_ptr<plansys2::PlannerClient> planner_client_;
|
||||||
};
|
};
|
||||||
|
|
||||||
int main(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>();
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue