Compare commits

...

5 Commits

19 changed files with 794 additions and 4 deletions

View File

@@ -76,7 +76,9 @@ GUI_ENVS=(
CUSTOM_VOLUMES+=("/etc/localtime:/etc/localtime:ro")
# Pass USB devices to container
USB_VOLUME+=("/dev/bus/usb:/dev/bus/usb")
#USB_VOLUME+=("/dev/bus/usb:/dev/bus/usb")
DEVICE_VOLUME+=("/dev:/dev:rw")
#USB_SERIAL+=("/dev/ttyACM0:/dev/ttyACM0")
## Additional environment variables
# Synchronize ROS_DOMAIN_ID with host
@@ -114,7 +116,9 @@ DOCKER_RUN_CMD=(
"${GPU_OPT}"
"${GPU_ENVS[@]/#/"--env "}"
"${CUSTOM_VOLUMES[@]/#/"--volume "}"
"${USB_VOLUME[@]/#/"--volume "}"
"${DEVICE_VOLUME[@]/#/"--volume "}"
#"${USB_VOLUME[@]/#/"--volume "}"
#"${USB_SERIAL[@]/#/"--volume "}"
"${CUSTOM_ENVS[@]/#/"--env "}"
"${TAG}"
"${CMD}"

View File

@@ -9,3 +9,22 @@ colcon build
source install/local_setup.bash
ros2 launch draw_svg draw_svg.launch.py
```
## xArm lite6
- web interface: http://192.168.1.150:18333
## ROS2 rpi4
https://github.com/ros-realtime/ros-realtime-rpi4-image/releases
After unpacking the tar file, flash it to sd card.
Log in with "ubuntu:ubuntu".
``` sh
sudo -i
loadkeys fi
passwd ubuntu #change from default 'ubuntu' to '1234'
apt-mark hold $(uname -r) linux-firmware u-boot-rpi u-boot-tools #prevent kernel updates
apt-mark hold libraspberrypi-bin libraspberrypi-dev libraspberrypi-doc libraspberrypi0
apt-mark hold raspberrypi-bootloader raspberrypi-kernel raspberrypi-kernel-headers
apt update && apt upgrade
```

View File

@@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 3.8)
project(axidraw_controller)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

View File

@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>axidraw_controller</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="root@todo.todo">root</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -2,6 +2,7 @@
from pyaxidraw import axidraw # import module
ad = axidraw.AxiDraw() # Initialize class
ad.interactive() # Enter interactive context
ad.options.port = "/dev/ttyAXI"
if not ad.connect(): # Open serial port to AxiDraw;
quit() # Exit, if no connection.
ad.options.units = 1 # set working units to cm.

View File

@@ -0,0 +1,361 @@
import os
from launch import LaunchDescription
from launch.actions import OpaqueFunction, IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from launch_ros.actions import Node
from ament_index_python import get_package_share_directory
from launch.launch_description_sources import load_python_launch_file_as_module
from launch import LaunchDescription
from launch.actions import RegisterEventHandler, EmitEvent
from launch.event_handlers import OnProcessExit
from launch.events import Shutdown
def launch_setup(context, *args, **kwargs):
robot_ip = LaunchConfiguration('robot_ip', default='192.168.1.150')
report_type = LaunchConfiguration('report_type', default='normal')
prefix = LaunchConfiguration('prefix', default='')
hw_ns = LaunchConfiguration('hw_ns', default='ufactory')
limited = LaunchConfiguration('limited', default=True)
effort_control = LaunchConfiguration('effort_control', default=False)
velocity_control = LaunchConfiguration('velocity_control', default=False)
add_gripper = LaunchConfiguration('add_gripper', default=False)
add_vacuum_gripper = LaunchConfiguration('add_vacuum_gripper', default=False)
dof = LaunchConfiguration('dof', default=6)
robot_type = LaunchConfiguration('robot_type', default='lite')
no_gui_ctrl = LaunchConfiguration('no_gui_ctrl', default=False)
add_other_geometry = LaunchConfiguration('add_other_geometry', default=False)
geometry_type = LaunchConfiguration('geometry_type', default='box')
geometry_mass = LaunchConfiguration('geometry_mass', default=0.1)
geometry_height = LaunchConfiguration('geometry_height', default=0.1)
geometry_radius = LaunchConfiguration('geometry_radius', default=0.1)
geometry_length = LaunchConfiguration('geometry_length', default=0.1)
geometry_width = LaunchConfiguration('geometry_width', default=0.1)
geometry_mesh_filename = LaunchConfiguration('geometry_mesh_filename', default='')
geometry_mesh_origin_xyz = LaunchConfiguration('geometry_mesh_origin_xyz', default='"0 0 0"')
geometry_mesh_origin_rpy = LaunchConfiguration('geometry_mesh_origin_rpy', default='"0 0 0"')
geometry_mesh_tcp_xyz = LaunchConfiguration('geometry_mesh_tcp_xyz', default='"0 0 0"')
geometry_mesh_tcp_rpy = LaunchConfiguration('geometry_mesh_tcp_rpy', default='"0 0 0"')
baud_checkset = LaunchConfiguration('baud_checkset', default=True)
default_gripper_baud = LaunchConfiguration('default_gripper_baud', default=2000000)
ros2_control_plugin = 'uf_robot_hardware/UFRobotSystemHardware'
controllers_name = LaunchConfiguration('controllers_name', default='controllers')
moveit_controller_manager_key = LaunchConfiguration('moveit_controller_manager_key', default='moveit_simple_controller_manager')
moveit_controller_manager_value = LaunchConfiguration('moveit_controller_manager_value', default='moveit_simple_controller_manager/MoveItSimpleControllerManager')
xarm_type = '{}{}'.format(robot_type.perform(context), dof.perform(context))
ros_namespace = LaunchConfiguration('ros_namespace', default='').perform(context)
use_sim_time = LaunchConfiguration('use_sim_time', default=False)
log_level = LaunchConfiguration("log_level", default='warn')
# # robot driver launch
# # xarm_api/launch/_robot_driver.launch.py
# robot_driver_launch = IncludeLaunchDescription(
# PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('xarm_api'), 'launch', '_robot_driver.launch.py'])),
# launch_arguments={
# 'robot_ip': robot_ip,
# 'report_type': report_type,
# 'dof': dof,
# 'hw_ns': hw_ns,
# 'add_gripper': add_gripper,
# 'prefix': prefix,
# 'baud_checkset': baud_checkset,
# 'default_gripper_baud': default_gripper_baud,
# 'robot_type': robot_type,
# }.items(),
# )
# robot description launch
# xarm_description/launch/_robot_description.launch.py
robot_description_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('xarm_description'), 'launch', '_robot_description.launch.py'])),
launch_arguments={
'prefix': prefix,
'hw_ns': hw_ns,
'limited': limited,
'effort_control': effort_control,
'velocity_control': velocity_control,
'add_gripper': add_gripper,
'add_vacuum_gripper': add_vacuum_gripper,
'dof': dof,
'robot_type': robot_type,
'ros2_control_plugin': ros2_control_plugin,
'joint_states_remapping': PathJoinSubstitution(['/', ros_namespace, hw_ns, 'joint_states']),
'add_other_geometry': add_other_geometry,
'geometry_type': geometry_type,
'geometry_mass': geometry_mass,
'geometry_height': geometry_height,
'geometry_radius': geometry_radius,
'geometry_length': geometry_length,
'geometry_width': geometry_width,
'geometry_mesh_filename': geometry_mesh_filename,
'geometry_mesh_origin_xyz': geometry_mesh_origin_xyz,
'geometry_mesh_origin_rpy': geometry_mesh_origin_rpy,
'geometry_mesh_tcp_xyz': geometry_mesh_tcp_xyz,
'geometry_mesh_tcp_rpy': geometry_mesh_tcp_rpy,
}.items(),
)
# robot_description_parameters
# xarm_moveit_config/launch/lib/robot_moveit_config_lib.py
moveit_config_package_name = 'xarm_moveit_config'
mod = load_python_launch_file_as_module(os.path.join(get_package_share_directory(moveit_config_package_name), 'launch', 'lib', 'robot_moveit_config_lib.py'))
get_xarm_robot_description_parameters = getattr(mod, 'get_xarm_robot_description_parameters')
robot_description_parameters = get_xarm_robot_description_parameters(
xacro_urdf_file=PathJoinSubstitution([FindPackageShare('xarm_description'), 'urdf', 'xarm_device.urdf.xacro']),
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
urdf_arguments={
'prefix': prefix,
'hw_ns': hw_ns.perform(context).strip('/'),
'limited': limited,
'effort_control': effort_control,
'velocity_control': velocity_control,
'add_gripper': add_gripper,
'add_vacuum_gripper': add_vacuum_gripper,
'dof': dof,
'robot_type': robot_type,
'ros2_control_plugin': ros2_control_plugin,
'add_other_geometry': add_other_geometry,
'geometry_type': geometry_type,
'geometry_mass': geometry_mass,
'geometry_height': geometry_height,
'geometry_radius': geometry_radius,
'geometry_length': geometry_length,
'geometry_width': geometry_width,
'geometry_mesh_filename': geometry_mesh_filename,
'geometry_mesh_origin_xyz': geometry_mesh_origin_xyz,
'geometry_mesh_origin_rpy': geometry_mesh_origin_rpy,
'geometry_mesh_tcp_xyz': geometry_mesh_tcp_xyz,
'geometry_mesh_tcp_rpy': geometry_mesh_tcp_rpy,
},
srdf_arguments={
'prefix': prefix,
'dof': dof,
'robot_type': robot_type,
'add_gripper': add_gripper,
'add_vacuum_gripper': add_vacuum_gripper,
'add_other_geometry': add_other_geometry,
},
arguments={
'context': context,
'xarm_type': xarm_type,
}
)
load_yaml = getattr(mod, 'load_yaml')
controllers_yaml = load_yaml(moveit_config_package_name, 'config', xarm_type, '{}.yaml'.format(controllers_name.perform(context)))
ompl_planning_yaml = load_yaml(moveit_config_package_name, 'config', xarm_type, 'ompl_planning.yaml')
kinematics_yaml = robot_description_parameters['robot_description_kinematics']
joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None)
if add_gripper.perform(context) in ('True', 'true'):
gripper_controllers_yaml = load_yaml(moveit_config_package_name, 'config', '{}_gripper'.format(robot_type.perform(context)), '{}.yaml'.format(controllers_name.perform(context)))
gripper_ompl_planning_yaml = load_yaml(moveit_config_package_name, 'config', '{}_gripper'.format(robot_type.perform(context)), 'ompl_planning.yaml')
gripper_joint_limits_yaml = load_yaml(moveit_config_package_name, 'config', '{}_gripper'.format(robot_type.perform(context)), 'joint_limits.yaml')
if gripper_controllers_yaml and 'controller_names' in gripper_controllers_yaml:
for name in gripper_controllers_yaml['controller_names']:
if name in gripper_controllers_yaml:
if name not in controllers_yaml['controller_names']:
controllers_yaml['controller_names'].append(name)
controllers_yaml[name] = gripper_controllers_yaml[name]
if gripper_ompl_planning_yaml:
ompl_planning_yaml.update(gripper_ompl_planning_yaml)
if joint_limits_yaml and gripper_joint_limits_yaml:
joint_limits_yaml['joint_limits'].update(gripper_joint_limits_yaml['joint_limits'])
add_prefix_to_moveit_params = getattr(mod, 'add_prefix_to_moveit_params')
add_prefix_to_moveit_params(
controllers_yaml=controllers_yaml, ompl_planning_yaml=ompl_planning_yaml,
kinematics_yaml=kinematics_yaml, joint_limits_yaml=joint_limits_yaml,
prefix=prefix.perform(context))
# Planning Configuration
ompl_planning_pipeline_config = {
'move_group': {
'planning_plugin': 'ompl_interface/OMPLPlanner',
'request_adapters': """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""",
'start_state_max_bounds_error': 0.1,
}
}
ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml)
# Moveit controllers Configuration
moveit_controllers = {
moveit_controller_manager_key.perform(context): controllers_yaml,
'moveit_controller_manager': moveit_controller_manager_value.perform(context),
}
# Trajectory Execution Configuration
trajectory_execution = {
'moveit_manage_controllers': True,
'trajectory_execution.allowed_execution_duration_scaling': 1.2,
'trajectory_execution.allowed_goal_duration_margin': 0.5,
'trajectory_execution.allowed_start_tolerance': 0.01,
'trajectory_execution.execution_duration_monitoring': False
}
plan_execution = {
'plan_execution.record_trajectory_state_frequency': 10.0,
}
planning_scene_monitor_parameters = {
'publish_planning_scene': True,
'publish_geometry_updates': True,
'publish_state_updates': True,
'publish_transforms_updates': True,
# "planning_scene_monitor_options": {
# "name": "planning_scene_monitor",
# "robot_description": "robot_description",
# "joint_state_topic": "/joint_states",
# "attached_collision_object_topic": "/move_group/planning_scene_monitor",
# "publish_planning_scene_topic": "/move_group/publish_planning_scene",
# "monitored_planning_scene_topic": "/move_group/monitored_planning_scene",
# "wait_for_initial_state_timeout": 10.0,
# },
}
# Start the actual move_group node/action server
move_group_node = Node(
package='moveit_ros_move_group',
executable='move_group',
output='screen',
parameters=[
robot_description_parameters,
ompl_planning_pipeline_config,
trajectory_execution,
plan_execution,
moveit_controllers,
planning_scene_monitor_parameters,
{'use_sim_time': use_sim_time},
],
)
# rviz with moveit configuration
# rviz_config_file = PathJoinSubstitution([FindPackageShare(moveit_config_package_name), 'config', xarm_type, 'planner.rviz' if no_gui_ctrl.perform(context) == 'true' else 'moveit.rviz'])
rviz_config_file = PathJoinSubstitution([FindPackageShare(moveit_config_package_name), 'rviz', 'planner.rviz' if no_gui_ctrl.perform(context) == 'true' else 'moveit.rviz'])
rviz2_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', rviz_config_file],
parameters=[
robot_description_parameters,
ompl_planning_pipeline_config,
{'use_sim_time': use_sim_time},
],
remappings=[
('/tf', 'tf'),
('/tf_static', 'tf_static'),
]
)
# Static TF
static_tf = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='static_transform_publisher',
output='screen',
arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'world', 'link_base'],
)
# joint state publisher node
joint_state_publisher_node = Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
output='screen',
parameters=[{'source_list': ['{}/joint_states'.format(hw_ns.perform(context))]}],
remappings=[
('follow_joint_trajectory', '{}{}_traj_controller/follow_joint_trajectory'.format(prefix.perform(context), xarm_type)),
],
)
# ros2 control launch
# xarm_controller/launch/_ros2_control.launch.py
ros2_control_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('xarm_controller'), 'launch', '_ros2_control.launch.py'])),
launch_arguments={
'robot_ip': robot_ip,
'report_type': report_type,
'baud_checkset': baud_checkset,
'default_gripper_baud': default_gripper_baud,
'prefix': prefix,
'hw_ns': hw_ns,
'limited': limited,
'effort_control': effort_control,
'velocity_control': velocity_control,
'add_gripper': add_gripper,
'add_vacuum_gripper': add_vacuum_gripper,
'dof': dof,
'robot_type': robot_type,
'ros2_control_plugin': ros2_control_plugin,
}.items(),
)
control_node = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=[
'{}{}_traj_controller'.format(prefix.perform(context), xarm_type),
'--controller-manager', '{}/controller_manager'.format(ros_namespace)
],
)
nodes = [
Node(
package="draw_svg",
executable="follow",
output="log",
arguments=["--ros-args", "--log-level", log_level],
parameters=[
#robot_description_parameters['robot_description'],
#robot_description_parameters['robot_description_semantic'],
#robot_description_parameters['robot_description_planning'],
#robot_description_parameters['robot_description_kinematics'],
robot_description_parameters,
{"use_sim_time": use_sim_time},
],
),
Node(
package="draw_svg",
executable="draw_svg.py",
output="log",
arguments=["--ros-args", "--log-level", log_level],
parameters=[{"use_sim_time": use_sim_time}],
),
]
return [
RegisterEventHandler(event_handler=OnProcessExit(
target_action=rviz2_node,
on_exit=[EmitEvent(event=Shutdown())]
)),
rviz2_node,
static_tf,
move_group_node,
robot_description_launch,
joint_state_publisher_node,
ros2_control_launch,
control_node,
# robot_driver_launch,
] + nodes
def generate_launch_description():
return LaunchDescription([
OpaqueFunction(function=launch_setup)
])

View File

@@ -55,7 +55,7 @@ class PublishTarget(Node):
def __init__(self):
super().__init__('publisher')
self.publisher_ = self.create_publisher(PoseStamped, '/target_pose', 10)
timer_period = 7.0 # seconds
timer_period = 4.0 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
@@ -66,7 +66,7 @@ class PublishTarget(Node):
#print(p.orientation)
xml = ET.parse('svg/test.svg')
svg = xml.getroot()
self.map_point = map_point_function(float(svg.get('width')), float(svg.get('height')), 0.1, 0.5, -0.2, 0.2)
self.map_point = map_point_function(float(svg.get('width')), float(svg.get('height')), 0.2, 0.4, -0.1, 0.1)
self.points = []
for child in svg:
if (child.tag == 'line'):

View File

@@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 3.8)
project(drawing_controller)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

View File

@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>drawing_controller</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="root@todo.todo">root</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,110 @@
#!/usr/bin/env python3
"""Sends motions individually to robot_controller"""
import rclpy
from geometry_msgs.msg import Pose, PoseStamped
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.node import Node
from rclpy.qos import QoSProfile
from random import uniform as rand
import math
#from tf2_ros.transformations import quaternion_from_euler
import lxml.etree as ET
def quaternion_from_euler(ai, aj, ak):
ai /= 2.0
aj /= 2.0
ak /= 2.0
ci = math.cos(ai)
si = math.sin(ai)
cj = math.cos(aj)
sj = math.sin(aj)
ck = math.cos(ak)
sk = math.sin(ak)
cc = ci*ck
cs = ci*sk
sc = si*ck
ss = si*sk
q = [0,0,0,0]
q[0] = cj*sc - sj*cs
q[1] = cj*ss + sj*cc
q[2] = cj*cs - sj*sc
q[3] = cj*cc + sj*ss
return q
def translate(val, lmin, lmax, rmin, rmax):
lspan = lmax - lmin
rspan = rmax - rmin
val = float(val - lmin) / float(lspan)
return rmin + (val * rspan)
def map_point_function(x_pixels, y_pixels, xlim_lower, xlim_upper, ylim_lower, ylim_upper):
def map_point(xpix,ypix):
x = translate(xpix, 0, x_pixels, xlim_lower, xlim_upper)
y = translate(ypix, 0, y_pixels, ylim_lower, ylim_upper)
return (x,y)
return map_point
class DrawingController(Node):
def __init__(self):
super().__init__('drawing_controller')
self.publisher_ = self.create_publisher(PoseStamped, '/target_pose', 10)
timer_period = 7.0 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
# TODO get dimensions from svg
#print(p)
#print(p.position)
#print(p.orientation)
xml = ET.parse('svg/test.svg')
svg = xml.getroot()
self.map_point = map_point_function(float(svg.get('width')), float(svg.get('height')), 0.1, 0.5, -0.2, 0.2)
self.points = []
for child in svg:
if (child.tag == 'line'):
self.points.append((float(child.get('x1')), float(child.get('y1'))))
self.points.append((float(child.get('x2')), float(child.get('y2'))))
def timer_callback(self):
next_point = self.points[self.i]
point = self.map_point(float(next_point[0]),float(next_point[1]))
p = Pose()
p.position.x = point[0]
p.position.y = point[1]
p.position.z = 0.1
q = quaternion_from_euler(0.0, math.pi, 0.0)
#p.orientation = q
p.orientation.x = q[0]
p.orientation.y = q[1]
p.orientation.z = q[2]
p.orientation.w = q[3]
ps = PoseStamped()
ps.pose = p
#print(ps)
self.publisher_.publish(ps)
self.get_logger().info('Publishing to /target_pose: "%s"' % p)
self.i = (self.i + 1) % len(self.points)
def main(args=None):
rclpy.init(args=args)
publisher = PublishTarget()
rclpy.spin(publisher)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
publisher.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":
main()

View File

@@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 3.8)
project(lite6_controller)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

View File

@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>lite6_controller</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="root@todo.todo">root</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,37 @@
cmake_minimum_required(VERSION 3.8)
project(robot_controller)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(robot_interfaces REQUIRED)
#add_executable(robotcontroller src/robotcontroller.cpp)
#ament_target_dependencies(robotcontroller rclcpp robot_interfaces)
install(TARGETS
talker
listener
DESTINATION lib/${PROJECT_NAME})
ament_package()

View File

@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>robot_controller</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="root@todo.todo">root</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,41 @@
#include <cstdio>
#include <rclcpp/rclcpp.hpp>
class RobotController : public rclcpp::Node
{
public:
/// Constructor
RobotController();
private:
/// Callback that executes path on robot
virtual void add(const std::shared_ptr<robot_interfaces::srv::AddThreeInts::Request> request,
std::shared_ptr<robot_interfaces::srv::AddThreeInts::Response> response);
};
RobotController::RobotController(string name) : Node(name)
{
// Subscribe to target pose
target_pose_sub_ = this->create_subscription<geometry_msgs::msg::PoseStamped>("/target_pose", rclcpp::QoS(1), std::bind(&MoveItFollowTarget::target_pose_callback, this, std::placeholders::_1));
RCLCPP_INFO(this->get_logger(), "Initialization successful.");
}
int main(int argc, char ** argv)
{
//rclcpp::init(argc, argv);
//auto target_follower = std::make_shared<MoveItFollowTarget>();
//rclcpp::executors::SingleThreadedExecutor executor;
//executor.add_node(target_follower);
//executor.spin();
//rclcpp::shutdown();
//return EXIT_SUCCESS;
(void) argc;
(void) argv;
printf("hello world\n");
return 0;
}

View File

@@ -0,0 +1,34 @@
cmake_minimum_required(VERSION 3.8)
project(robot_interfaces)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Motion.msg"
"srv/ExecuteMotion.srv"
DEPENDENCIES geometry_msgs # Add packages that above messages depend on, in this case geometry_msgs for Sphere.msg
)
ament_package()

View File

@@ -0,0 +1,5 @@
# A single motion, consisting of a list of timestamped points
geometry_msgs/PoseStamped[] path
float64 acceleration
float64 velocity

View File

@@ -0,0 +1,26 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>robot_interfaces</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="root@todo.todo">root</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>geometry_msgs</depend>
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,5 @@
# Motion service
Motion motion
---
string status