Compare commits

23 Commits

Author SHA1 Message Date
5591cdabc9 Add script 2023-05-04 10:55:41 +03:00
7ce34b4834 Update axidraw conf 2023-04-28 15:47:51 +03:00
9e191df7e4 Axidraw config.yaml support 2023-04-28 15:43:19 +03:00
edcdcb9131 Update mount to rw 2023-04-28 13:09:46 +03:00
47360764ea Update readme 2023-04-28 12:56:12 +03:00
2238952f34 Add default configs 2023-04-28 12:45:47 +03:00
55be0910d5 Update docs and instructions 2023-04-28 12:38:56 +03:00
d3e533fdde Add config to container and documentation 2023-04-28 12:16:11 +03:00
45a3a3ac4d Add config file support 2023-04-28 11:34:37 +03:00
bdcccdc06e Merge branch 'config_yaml' into dev 2023-04-28 11:19:16 +03:00
cdef55b647 Expose working lite6 config 2023-04-28 11:16:41 +03:00
c421ef4482 Add svgpath to log 2023-04-11 12:02:55 +03:00
5145ffa6ac Adjust lite6 params 2023-04-11 12:02:47 +03:00
7f547c65f7 Expose ros2 params and load config yaml 2023-04-11 11:31:38 +03:00
925a9b42c7 Improve logging 2023-04-04 12:08:53 +03:00
5a00d7b258 Adjust lite6 params 2023-04-03 17:59:29 +03:00
28bf1413c2 Finish xarm calibration implementation 2023-04-03 17:58:32 +03:00
2372404732 Set new parameters for xArm 2023-04-03 15:02:13 +03:00
d58b968536 Fix planning 2023-04-03 12:34:28 +03:00
931ffe54b7 Adjust simplification epsilon 2023-03-31 15:10:21 +03:00
93e5707ca9 Allow for image folder to be passed to container 2023-03-31 14:09:08 +03:00
fde362b526 Set sampling points to 1000 2023-03-31 13:54:31 +03:00
0c2aff9fbd Set bezier control points to 50 2023-03-31 12:58:12 +03:00
21 changed files with 448 additions and 183 deletions

View File

@@ -12,6 +12,8 @@ ENV WS_INSTALL_DIR=${WS_DIR}/install
ENV WS_LOG_DIR=${WS_DIR}/log ENV WS_LOG_DIR=${WS_DIR}/log
WORKDIR ${WS_DIR} WORKDIR ${WS_DIR}
COPY config.yaml ${WS_DIR}/
### Install Gazebo ### Install Gazebo
ARG IGNITION_VERSION=fortress ARG IGNITION_VERSION=fortress
ENV IGNITION_VERSION=${IGNITION_VERSION} ENV IGNITION_VERSION=${IGNITION_VERSION}
@@ -25,6 +27,9 @@ RUN apt-get update && \
apt-get install -yq python3-pil.imagetk && \ apt-get install -yq python3-pil.imagetk && \
apt-get install -yq ros-${ROS_DISTRO}-pilz-industrial-motion-planner && \ apt-get install -yq ros-${ROS_DISTRO}-pilz-industrial-motion-planner && \
apt-get install -yq tmux && \ apt-get install -yq tmux && \
apt-get install -yq nano && \
apt-get install -yq vim && \
apt-get install -yq less && \
apt-get install -yq python3-pip && \ apt-get install -yq python3-pip && \
apt-get install -yq ros-${ROS_DISTRO}-desktop && \ apt-get install -yq ros-${ROS_DISTRO}-desktop && \
apt-get install -yq ros-${ROS_DISTRO}-rclcpp-components apt-get install -yq ros-${ROS_DISTRO}-rclcpp-components
@@ -75,7 +80,7 @@ RUN source "/opt/ros/${ROS_DISTRO}/setup.bash" && \
rm -rf ${WS_LOG_DIR} rm -rf ${WS_LOG_DIR}
# Copy example svg images # Copy example svg images
COPY ./svg svg COPY ./svg test-images
### Add workspace to the ROS entrypoint ### Add workspace to the ROS entrypoint
### Source ROS workspace inside `~/.bashrc` to enable autocompletion ### Source ROS workspace inside `~/.bashrc` to enable autocompletion

View File

@@ -34,13 +34,23 @@ If active changes are being made, run:
bash .docker/devel.bash bash .docker/devel.bash
``` ```
This will mount the host `drawing-robot-ros2` directory in the container at `src/drawing-robot-ros2`. This will mount the host `drawing-robot-ros2` directory in the container at `src/drawing-robot-ros2`.
If using podman instead of docker using the following will allow the container to access `/dev/` which is needed by the axidraw robot.
Optionally you can pass a directory to the container with
``` sh
bash .docker/run.bash -v PATH_TO_SVG:/svg:rw
```
This will mount the given path to /svg in read-write mode in the container.
#### Podman issues
If using podman instead of docker, using the following will allow the container to access `/dev/` which is needed by the axidraw robot.
``` sh ``` sh
sudo bash .docker/build.bash sudo bash .docker/build.bash
``` ```
``` sh ``` sh
sudo bash .docker/devel.bash sudo bash .docker/devel.bash
``` ```
Adding sudo may cause gazebo not to work, so it is recommended to use docker instead of podman.
## TODO Building locally ## TODO Building locally
@@ -67,28 +77,42 @@ DummyController echoes Motion messages to the terminal.
ros2 run robot_controller dummy_controller ros2 run robot_controller dummy_controller
``` ```
### AxidrawController
AxidrawController draws on the axidraw robot. AxidrawController draws on the axidraw robot.
Find the serial device in "/dev/", it is usually named "/dev/ttyACMX" where X is usually 0. Find the serial device in "/dev/", it is usually named "/dev/ttyACMX" where X is usually 0.
Try a different serial port if the axidraw_controller continuously logs a message about failing to connect. Try a different serial port if the axidraw_controller continuously logs a message about failing to connect.
``` sh ``` sh
ros2 launch axidraw_controller axidraw_controller.launch.py serial_port:=/dev/ttyACM0 ros2 launch axidraw_controller axidraw_controller.launch.py serial_port:=/dev/ttyACM0 config:=./config.yaml
``` ```
### Lite6Controller
This starts the simulated lite6 This starts the simulated lite6
``` sh ``` sh
ros2 launch lite6_controller lite6_gazebo.launch.py ros2 launch lite6_controller lite6_gazebo.launch.py config:=./config.yaml
``` ```
This runs the real lite6 This runs the real lite6
``` sh ``` sh
ros2 launch lite6_controller lite6_real.launch.py ros2 launch lite6_controller lite6_real.launch.py config:=./config.yaml
``` ```
This runs the real lite6 without Rviz (can be run on headless device over ssh) This runs the real lite6 without Rviz (can be run on headless device over ssh)
``` sh ``` sh
ros2 launch lite6_controller lite6_real_no_gui.launch.py ros2 launch lite6_controller lite6_real_no_gui.launch.py config:=./config.yaml
``` ```
Before using the real lite6, it is recommended to run the calibration program.
A lite6_controller must be running for calibration.
This can be used to measure the Z height for a specific pen.
The program also moves the arm to a known default position.
``` sh
ros2 run lite6_controller lite6_calibration
```
Follow the instructions, pressing enter when prompted.
Change the Z-offset value accordingly.
Restart the running lite6_controller after calibration.
### DrawingController ### DrawingController
Once a RobotController is running, simultaneously (using tmux or another terminal) run Once a RobotController is running, simultaneously (using tmux or another terminal) run
``` sh ``` sh

26
config.yaml Normal file
View File

@@ -0,0 +1,26 @@
/robot_controller:
ros__parameters:
lite6_x_limit_lower: 0.1
lite6_x_limit_upper: 0.305
lite6_y_limit_lower: -0.1475
lite6_y_limit_upper: 0.1475
lite6_z_lift_amount: 0.01
lite6_z_offset: 0.201942
lite6_blend_radius: 0.0
lite6_max_velocity_scaling_factor: 1.0
lite6_max_acceleration_scaling_factor: 0.9
/axidraw_serial:
ros__parameters:
axidraw_accel: 100
axidraw_speed_pendown: 50
axidraw_speed_penup: 50
axidraw_const_speed: false
axidraw_pen_delay_down: 0
axidraw_pen_delay_up: 0
axidraw_pen_pos_down: 40
axidraw_pen_pos_up: 60
axidraw_pen_rate_lower: 50
axidraw_pen_rate_raise: 75

12
scripts/log_drawing.sh Executable file
View File

@@ -0,0 +1,12 @@
#!/usr/bin/env sh
# Logs drawn images
# ./log_drawing.sh ROBOTNAME SVG
# ROBOTNAME: robot name (logged before output)
# SVG: svg path to be drawn
date >> data.txt
echo $1 >> data.txt
ros2 run drawing_controller drawing_controller $2 2>&1 | grep 'Results' | tee -a data.txt
echo '\n' >> data.txt
#{'svg processing time': '00:00:02', 'failure': 65, 'total time': '00:00:09', 'drawing time': '00:00:06'}

View File

@@ -40,6 +40,11 @@ install(PROGRAMS
DESTINATION lib/${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME}
) )
install(DIRECTORY
config
DESTINATION share/${PROJECT_NAME}
)
if(BUILD_TESTING) if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED) find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights # the following line skips the linter which checks for copyrights

View File

@@ -0,0 +1,12 @@
/axidraw_serial:
ros__parameters:
axidraw_accel: 100
axidraw_const_speed: false
axidraw_pen_delay_down: 0
axidraw_pen_delay_up: 0
axidraw_pen_pos_down: 40
axidraw_pen_pos_up: 60
axidraw_pen_rate_lower: 50
axidraw_pen_rate_raise: 75
axidraw_speed_pendown: 50
axidraw_speed_penup: 50

View File

@@ -1,4 +1,5 @@
import os import os
import yaml
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import OpaqueFunction, IncludeLaunchDescription, DeclareLaunchArgument from launch.actions import OpaqueFunction, IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.launch_description_sources import PythonLaunchDescriptionSource
@@ -18,6 +19,13 @@ def launch_setup(context, *args, **kwargs):
serial_port = LaunchConfiguration('serial_port', default='/dev/ttyACM0') serial_port = LaunchConfiguration('serial_port', default='/dev/ttyACM0')
log_level = LaunchConfiguration("log_level", default='info') log_level = LaunchConfiguration("log_level", default='info')
config = LaunchConfiguration("config", default=PathJoinSubstitution([FindPackageShare('axidraw_controller'), 'config', 'config.yaml']))
robotcontroller_config = config.perform(context)
with open(robotcontroller_config, 'r') as f:
axidraw_config = yaml.safe_load(f)['/axidraw_serial']['ros__parameters']
print(f'Loaded configuration: {axidraw_config}')
nodes = [ nodes = [
Node( Node(
package="axidraw_controller", package="axidraw_controller",
@@ -34,6 +42,7 @@ def launch_setup(context, *args, **kwargs):
arguments=["--ros-args", "--log-level", log_level], arguments=["--ros-args", "--log-level", log_level],
parameters=[ parameters=[
{"serial_port": serial_port}, {"serial_port": serial_port},
axidraw_config,
], ],
), ),
] ]

View File

@@ -61,11 +61,18 @@ class AxidrawSerial(Node):
return False return False
self.ad.options.units = 2 # set working units to mm. self.ad.options.units = 2 # set working units to mm.
self.ad.options.model = 2 # set model to AxiDraw V3/A3 self.ad.options.model = 2 # set model to AxiDraw V3/A3
self.ad.options.speed_pendown = 100 # 100% speed
self.ad.options.speed_penup = 100 # 100% speed self.ad.options.speed_pendown = self.get_parameter('axidraw_speed_pendown').get_parameter_value().integer_value # Maximum XY speed when the pen is down (plotting).
self.ad.options.accel = 100 # 100% speed self.ad.options.speed_penup = self.get_parameter('axidraw_speed_penup').get_parameter_value().integer_value # Maximum XY speed when the pen is up.
self.ad.options.pen_rate_lower = 100 # 100% speed self.ad.options.accel = self.get_parameter('axidraw_accel').get_parameter_value().integer_value # Relative acceleration/deceleration speed.
self.ad.options.pen_rate_raise = 100 # 100% speed #self.get_logger().error('accel:{}'.format(self.get_parameter('axidraw_accel').get_parameter_value().integer_value))
self.ad.options.pen_pos_down = self.get_parameter('axidraw_pen_pos_down').get_parameter_value().integer_value #Pen height when the pen is down (plotting).
self.ad.options.pen_pos_up = self.get_parameter('axidraw_pen_pos_up').get_parameter_value().integer_value #Pen height when the pen is up.
self.ad.options.pen_rate_lower = self.get_parameter('axidraw_pen_rate_lower').get_parameter_value().integer_value # Speed of lowering the pen-lift motor.
self.ad.options.pen_rate_raise = self.get_parameter('axidraw_pen_rate_raise').get_parameter_value().integer_value #Speed of raising the pen-lift motor.
self.ad.options.const_speed = self.get_parameter('axidraw_const_speed').get_parameter_value().bool_value #Option: Use constant speed when pen is down.
self.ad.options.pen_delay_down = self.get_parameter('axidraw_pen_delay_down').get_parameter_value().integer_value #Added delay after lowering pen.
self.ad.options.pen_delay_up = self.get_parameter('axidraw_pen_delay_up').get_parameter_value().integer_value #Added delay after raising pen.
self.ad.update() # Process changes to options self.ad.update() # Process changes to options
self.status["serial"] = "ready" self.status["serial"] = "ready"
self.status["motion"] = "ready" self.status["motion"] = "ready"
@@ -87,6 +94,17 @@ class AxidrawSerial(Node):
self.declare_parameter('serial_port', '/dev/ttyACM0') self.declare_parameter('serial_port', '/dev/ttyACM0')
port = self.get_parameter('serial_port').get_parameter_value().string_value port = self.get_parameter('serial_port').get_parameter_value().string_value
self.declare_parameter('axidraw_speed_pendown', 100)
self.declare_parameter('axidraw_speed_penup', 100)
self.declare_parameter('axidraw_accel', 100)
self.declare_parameter('axidraw_pen_pos_down', 40)
self.declare_parameter('axidraw_pen_pos_up', 60)
self.declare_parameter('axidraw_pen_rate_lower', 50)
self.declare_parameter('axidraw_pen_rate_raise', 75)
self.declare_parameter('axidraw_const_speed', False)
self.declare_parameter('axidraw_pen_delay_down', 0)
self.declare_parameter('axidraw_pen_delay_up', 0)
self.status_srv = self.create_service(Status, 'axidraw_status', self.get_status) self.status_srv = self.create_service(Status, 'axidraw_status', self.get_status)
while not self.init_serial(port): while not self.init_serial(port):

View File

@@ -1,5 +1,5 @@
cartesian_limits: cartesian_limits:
max_trans_vel: 2.0 max_trans_vel: 0.4
max_trans_acc: 3.00 max_trans_acc: 4.00
max_trans_dec: -5.0 max_trans_dec: -5.0
max_rot_vel: 1.57 max_rot_vel: 1.57

View File

@@ -4,31 +4,31 @@
joint_limits: joint_limits:
joint1: joint1:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 10.14 max_velocity: 4.14
has_acceleration_limits: true has_acceleration_limits: true
max_acceleration: 20.0 max_acceleration: 30.0
joint2: joint2:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 10.14 max_velocity: 4.14
has_acceleration_limits: true has_acceleration_limits: true
max_acceleration: 20.0 max_acceleration: 30.0
joint3: joint3:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 10.14 max_velocity: 4.14
has_acceleration_limits: true has_acceleration_limits: true
max_acceleration: 20.0 max_acceleration: 30.0
joint4: joint4:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 10.14 max_velocity: 4.14
has_acceleration_limits: true has_acceleration_limits: true
max_acceleration: 20.0 max_acceleration: 30.0
joint5: joint5:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 10.14 max_velocity: 4.14
has_acceleration_limits: true has_acceleration_limits: true
max_acceleration: 20.0 max_acceleration: 30.0
joint6: joint6:
has_velocity_limits: true has_velocity_limits: true
max_velocity: 10.14 max_velocity: 4.14
has_acceleration_limits: true has_acceleration_limits: true
max_acceleration: 20.0 max_acceleration: 30.0

View File

@@ -17,6 +17,8 @@ from robot_interfaces.msg import Motion
import sys import sys
from copy import deepcopy from copy import deepcopy
import time
from drawing_controller.svg_processor import SVGProcessor from drawing_controller.svg_processor import SVGProcessor
def quaternion_from_euler(ai, aj, ak): def quaternion_from_euler(ai, aj, ak):
@@ -61,13 +63,17 @@ class DrawingController(Node):
def __init__(self, svgpath): def __init__(self, svgpath):
super().__init__('drawing_controller') super().__init__('drawing_controller')
#self.publisher_ = self.create_publisher(PoseStamped, '/target_pose', 10) #self.publisher_ = self.create_publisher(PoseStamped, '/target_pose', 10)
timer_period = 1.0 # seconds timer_period = 0.1 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback) self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0 self.i = 0
self.busy = False self.busy = False
self._action_client = ActionClient(self, ExecuteMotion, 'execute_motion') self._action_client = ActionClient(self, ExecuteMotion, 'execute_motion')
self.results = {}
self.svg_start_time = time.time()
xml = ET.parse(svgpath) xml = ET.parse(svgpath)
svg = xml.getroot() 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.1, 0.5, -0.2, 0.2)
@@ -85,7 +91,11 @@ class DrawingController(Node):
self.svg_processor = SVGProcessor(self.get_logger()) self.svg_processor = SVGProcessor(self.get_logger())
self.svg = self.svg_processor.process_svg(svgpath) self.svg = self.svg_processor.process_svg(svgpath)
self.get_logger().info('Ready to begin executing motions') self.results['svg path'] = svgpath
self.results['svg processing time'] = self.timestr(time.time() - self.svg_start_time)
self.start_time = time.time()
self.get_logger().info('SVG processing finished, executing motions')
def send_goal(self, motion): def send_goal(self, motion):
self.busy = True self.busy = True
@@ -101,22 +111,23 @@ class DrawingController(Node):
def goal_response_callback(self, future): def goal_response_callback(self, future):
goal_handle = future.result() goal_handle = future.result()
if not goal_handle.accepted: if not goal_handle.accepted:
self.get_logger().info('Goal rejected :(') self.get_logger().debug('Goal rejected :(')
return return
self.get_logger().info('Goal accepted :)') self.get_logger().debug('Goal accepted :)')
self._get_result_future = goal_handle.get_result_async() self._get_result_future = goal_handle.get_result_async()
self._get_result_future.add_done_callback(self.get_result_callback) self._get_result_future.add_done_callback(self.get_result_callback)
def get_result_callback(self, future): def get_result_callback(self, future):
result = future.result().result result = future.result().result
self.get_logger().info('Result: {0}'.format(result)) self.results.update({ result.result: self.results.get(result.result, 0) + 1 })
self.get_logger().info('Result: {0}'.format(result.result))
self.busy = False self.busy = False
def feedback_callback(self, feedback_msg): def feedback_callback(self, feedback_msg):
feedback = feedback_msg.feedback feedback = feedback_msg.feedback
self.get_logger().info('Received feedback: {0}'.format(feedback)) self.get_logger().debug('Received feedback: {0}'.format(feedback))
def append_points(self, motion, points): def append_points(self, motion, points):
for point in points: for point in points:
@@ -135,17 +146,23 @@ class DrawingController(Node):
ps.pose = p ps.pose = p
motion.path.append(ps) motion.path.append(ps)
def timestr(self, t):
return time.strftime("%H:%M:%S", time.gmtime(t))
def timer_callback(self): def timer_callback(self):
if self.busy: if self.busy:
return return
if self.i >= len(self.svg): if self.i >= len(self.svg):
self.results['total time'] = self.timestr(time.time() - self.svg_start_time)
self.results['drawing time'] = self.timestr(time.time() - self.start_time)
self.get_logger().info('Finished executing all motions from SVG') self.get_logger().info('Finished executing all motions from SVG')
self.get_logger().info('Results: {}'.format(self.results))
exit() exit()
next_motion = self.svg[self.i] next_motion = self.svg[self.i]
motion = Motion() motion = Motion()
self.append_points(motion, next_motion) self.append_points(motion, next_motion)
self.i = self.i + 1 self.i = self.i + 1
self.get_logger().info('Executing motion: {}...'.format(motion.path[:10])) self.get_logger().info('Executing motion: {}/{}'.format(self.i, len(self.svg)))
self.send_goal(motion) self.send_goal(motion)

View File

@@ -11,7 +11,7 @@ class SVGPathParser():
self.map_point = map_point self.map_point = map_point
def tokenize(self, pathstr): def tokenize(self, pathstr):
self.logger.info("Tokenizing path :'{}...' with {} characters".format(pathstr[:40], len(pathstr))) self.logger.debug("Tokenizing path :'{}...' with {} characters".format(pathstr[:40], len(pathstr)))
path = [] path = []
i = 0 i = 0
while i < len(pathstr): while i < len(pathstr):
@@ -53,7 +53,7 @@ class SVGPathParser():
Returns: Returns:
primitive_fn (): primitive_fn ():
''' '''
self.logger.info("Parsing path :'{}...' with {} tokens".format(path[:20], len(path))) self.logger.debug("Parsing path :'{}...' with {} tokens".format(path[:20], len(path)))
x = 0.0 x = 0.0
y = 0.0 y = 0.0
i = 0 i = 0
@@ -115,7 +115,7 @@ class SVGPathParser():
maxval = np.amax(np.absolute(control_points)) maxval = np.amax(np.absolute(control_points))
#print('maxxv', maxval) #print('maxxv', maxval)
#control_points = control_points / maxval #normalize values #control_points = control_points / maxval #normalize values
n = 500 n = 100
curve = cf.bezier(control_points) curve = cf.bezier(control_points)
lin = np.linspace(curve.start(0), curve.end(0), n) lin = np.linspace(curve.start(0), curve.end(0), n)
coordinates = curve(lin) coordinates = curve(lin)
@@ -140,7 +140,7 @@ class SVGPathParser():
nonlocal x nonlocal x
nonlocal y nonlocal y
control_points = np.array(control_points) control_points = np.array(control_points)
n = 500 n = 100
curve = cf.bezier(control_points, quadratic=True) curve = cf.bezier(control_points, quadratic=True)
lin = np.linspace(curve.start(0), curve.end(0), n) lin = np.linspace(curve.start(0), curve.end(0), n)
coordinates = curve(lin) coordinates = curve(lin)
@@ -289,5 +289,5 @@ class SVGPathParser():
self.logger.error("SVG path parser panic mode at '{}'".format(w)) self.logger.error("SVG path parser panic mode at '{}'".format(w))
i += 1 i += 1
self.logger.info("Finished parsing path :'{}...' with {} points".format(output[:3], len(output))) self.logger.debug("Finished parsing path :'{}...' with {} points".format(output[:3], len(output)))
return output return output

View File

@@ -197,8 +197,7 @@ class SVGProcessor():
Simplify line with https://pypi.org/project/simplification/ Simplify line with https://pypi.org/project/simplification/
""" """
# For RDP, Try an epsilon of 1.0 to start with. Other sensible values include 0.01, 0.001 # For RDP, Try an epsilon of 1.0 to start with. Other sensible values include 0.01, 0.001
#epsilon = 0.009 epsilon = 0.00005
epsilon = 0.0005
tmp = [] tmp = []
out = [] out = []

View File

@@ -72,4 +72,9 @@ install(TARGETS
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY
config
DESTINATION share/${PROJECT_NAME}
)
ament_package() ament_package()

View File

@@ -0,0 +1,13 @@
/robot_controller:
ros__parameters:
lite6_x_limit_lower: 0.1
lite6_x_limit_upper: 0.305
lite6_y_limit_lower: -0.1475
lite6_y_limit_upper: 0.1475
lite6_z_lift_amount: 0.01
lite6_z_offset: 0.1475
lite6_blend_radius: 0.0
lite6_max_velocity_scaling_factor: 1.0
lite6_max_acceleration_scaling_factor: 0.9

View File

@@ -2,6 +2,7 @@
"""Launch Python example for following a target""" """Launch Python example for following a target"""
import os import os
import yaml
from ament_index_python import get_package_share_directory from ament_index_python import get_package_share_directory
from launch.launch_description_sources import load_python_launch_file_as_module from launch.launch_description_sources import load_python_launch_file_as_module
from launch import LaunchDescription from launch import LaunchDescription
@@ -19,6 +20,7 @@ def launch_setup(context, *args, **kwargs):
log_level = LaunchConfiguration("log_level", default='info') log_level = LaunchConfiguration("log_level", default='info')
rviz_config = LaunchConfiguration('rviz_config', default=os.path.join(get_package_share_directory("custom_xarm_description"), "rviz", "display.rviz")) rviz_config = LaunchConfiguration('rviz_config', default=os.path.join(get_package_share_directory("custom_xarm_description"), "rviz", "display.rviz"))
prefix = LaunchConfiguration('prefix', default='') prefix = LaunchConfiguration('prefix', default='')
hw_ns = LaunchConfiguration('hw_ns', default='xarm') hw_ns = LaunchConfiguration('hw_ns', default='xarm')
limited = LaunchConfiguration('limited', default=False) limited = LaunchConfiguration('limited', default=False)
@@ -54,6 +56,8 @@ def launch_setup(context, *args, **kwargs):
moveit_controller_manager_key = LaunchConfiguration('moveit_controller_manager_key', default='moveit_simple_controller_manager') 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') moveit_controller_manager_value = LaunchConfiguration('moveit_controller_manager_value', default='moveit_simple_controller_manager/MoveItSimpleControllerManager')
config = LaunchConfiguration("config", default=PathJoinSubstitution([FindPackageShare('lite6_controller'), 'config', 'config.yaml']))
# robot moveit common launch # robot moveit common launch
# xarm_moveit_config/launch/_robot_moveit_common.launch.py # xarm_moveit_config/launch/_robot_moveit_common.launch.py
robot_moveit_common_launch = IncludeLaunchDescription( robot_moveit_common_launch = IncludeLaunchDescription(
@@ -263,6 +267,12 @@ def launch_setup(context, *args, **kwargs):
kinematics_yaml = robot_description_parameters['robot_description_kinematics'] kinematics_yaml = robot_description_parameters['robot_description_kinematics']
joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None) joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None)
robotcontroller_config = config.perform(context)
with open(robotcontroller_config, 'r') as f:
lite6_config = yaml.safe_load(f)
print(f'Loaded configuration: {lite6_config}')
robot_description_parameters.update(lite6_config['/robot_controller']['ros__parameters'])
#cartesian_limits = load_yaml(moveit_config_package_name, 'config', xarm_type, 'cartesian_limits.yaml') #cartesian_limits = load_yaml(moveit_config_package_name, 'config', xarm_type, 'cartesian_limits.yaml')
#robot_description_parameters['robot_description_planning']['cartesian_limits'] = cartesian_limits['cartesian_limits'] #robot_description_parameters['robot_description_planning']['cartesian_limits'] = cartesian_limits['cartesian_limits']
#input(joint_limits_yaml) #input(joint_limits_yaml)
@@ -382,15 +392,8 @@ def launch_setup(context, *args, **kwargs):
'publish_geometry_updates': True, 'publish_geometry_updates': True,
'publish_state_updates': True, 'publish_state_updates': True,
'publish_transforms_updates': True, 'publish_transforms_updates': True,
# "planning_scene_monitor_options": { 'publish_robot_description': True,
# "name": "planning_scene_monitor", 'publish_robot_description_semantic' :True,
# "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 # Start the actual move_group node/action server

View File

@@ -1,4 +1,5 @@
import os import os
import yaml
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import OpaqueFunction, IncludeLaunchDescription, DeclareLaunchArgument from launch.actions import OpaqueFunction, IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.launch_description_sources import PythonLaunchDescriptionSource
@@ -15,6 +16,7 @@ from launch.events import Shutdown
def launch_setup(context, *args, **kwargs): def launch_setup(context, *args, **kwargs):
robot_ip = LaunchConfiguration('robot_ip', default='192.168.1.150') robot_ip = LaunchConfiguration('robot_ip', default='192.168.1.150')
report_type = LaunchConfiguration('report_type', default='normal') report_type = LaunchConfiguration('report_type', default='normal')
prefix = LaunchConfiguration('prefix', default='') prefix = LaunchConfiguration('prefix', default='')
@@ -55,6 +57,8 @@ def launch_setup(context, *args, **kwargs):
use_sim_time = LaunchConfiguration('use_sim_time', default=False) use_sim_time = LaunchConfiguration('use_sim_time', default=False)
log_level = LaunchConfiguration("log_level", default='warn') log_level = LaunchConfiguration("log_level", default='warn')
config = LaunchConfiguration("config", default=PathJoinSubstitution([FindPackageShare('lite6_controller'), 'config', 'config.yaml']))
# # robot driver launch # # robot driver launch
# # xarm_api/launch/_robot_driver.launch.py # # xarm_api/launch/_robot_driver.launch.py
# robot_driver_launch = IncludeLaunchDescription( # robot_driver_launch = IncludeLaunchDescription(
@@ -164,6 +168,12 @@ def launch_setup(context, *args, **kwargs):
joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None) joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None)
robotcontroller_config = config.perform(context)
with open(robotcontroller_config, 'r') as f:
lite6_config = yaml.safe_load(f)
print(f'Loaded configuration: {lite6_config}')
robot_description_parameters.update(lite6_config['/robot_controller']['ros__parameters'])
if add_gripper.perform(context) in ('True', 'true'): 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_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_ompl_planning_yaml = load_yaml(moveit_config_package_name, 'config', '{}_gripper'.format(robot_type.perform(context)), 'ompl_planning.yaml')
@@ -227,15 +237,8 @@ def launch_setup(context, *args, **kwargs):
'publish_geometry_updates': True, 'publish_geometry_updates': True,
'publish_state_updates': True, 'publish_state_updates': True,
'publish_transforms_updates': True, 'publish_transforms_updates': True,
# "planning_scene_monitor_options": { 'publish_robot_description': True,
# "name": "planning_scene_monitor", 'publish_robot_description_semantic' :True,
# "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,
# },
} }

View File

@@ -1,4 +1,5 @@
import os import os
import yaml
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import OpaqueFunction, IncludeLaunchDescription, DeclareLaunchArgument from launch.actions import OpaqueFunction, IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.launch_description_sources import PythonLaunchDescriptionSource
@@ -15,6 +16,7 @@ from launch.events import Shutdown
def launch_setup(context, *args, **kwargs): def launch_setup(context, *args, **kwargs):
robot_ip = LaunchConfiguration('robot_ip', default='192.168.1.150') robot_ip = LaunchConfiguration('robot_ip', default='192.168.1.150')
report_type = LaunchConfiguration('report_type', default='normal') report_type = LaunchConfiguration('report_type', default='normal')
prefix = LaunchConfiguration('prefix', default='') prefix = LaunchConfiguration('prefix', default='')
@@ -55,6 +57,8 @@ def launch_setup(context, *args, **kwargs):
use_sim_time = LaunchConfiguration('use_sim_time', default=False) use_sim_time = LaunchConfiguration('use_sim_time', default=False)
log_level = LaunchConfiguration("log_level", default='warn') log_level = LaunchConfiguration("log_level", default='warn')
config = LaunchConfiguration("config", default=PathJoinSubstitution([FindPackageShare('lite6_controller'), 'config', 'config.yaml']))
# # robot driver launch # # robot driver launch
# # xarm_api/launch/_robot_driver.launch.py # # xarm_api/launch/_robot_driver.launch.py
# robot_driver_launch = IncludeLaunchDescription( # robot_driver_launch = IncludeLaunchDescription(
@@ -155,6 +159,12 @@ def launch_setup(context, *args, **kwargs):
kinematics_yaml = robot_description_parameters['robot_description_kinematics'] kinematics_yaml = robot_description_parameters['robot_description_kinematics']
joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None) joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None)
robotcontroller_config = config.perform(context)
with open(robotcontroller_config, 'r') as f:
lite6_config = yaml.safe_load(f)
print(f'Loaded configuration: {lite6_config}')
robot_description_parameters.update(lite6_config['/robot_controller']['ros__parameters'])
# FIX acceleration limits # FIX acceleration limits
#for i in range(1,7): #for i in range(1,7):
# joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True # joint_limits_yaml['joint_limits']['joint{}'.format(i)]['has_acceleration_limits'] = True
@@ -233,15 +243,8 @@ def launch_setup(context, *args, **kwargs):
'publish_geometry_updates': True, 'publish_geometry_updates': True,
'publish_state_updates': True, 'publish_state_updates': True,
'publish_transforms_updates': True, 'publish_transforms_updates': True,
# "planning_scene_monitor_options": { 'publish_robot_description': True,
# "name": "planning_scene_monitor", 'publish_robot_description_semantic' :True,
# "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 # Start the actual move_group node/action server

View File

@@ -5,6 +5,15 @@
#include <iostream> #include <iostream>
#include <string> #include <string>
// MoveIt
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
const std::string MOVE_GROUP = "lite6";
std::shared_ptr<rclcpp::Node> node;
void exit_sig_handler(int signum) void exit_sig_handler(int signum)
{ {
@@ -16,24 +25,31 @@ void wait()
{ {
do do
{ {
std::cout << '\n' << "Press a key to continue..."; std::cout << "Press a key to continue...";
} while (std::cin.get() != '\n'); } while (std::cin.get() != '\n');
} }
void println(std::string s) { void println(std::string s)
{
std::cout << s << std::endl; std::cout << s << std::endl;
} }
void print_joints(std::vector<float> jnts) { void print_joints(std::vector<float> jnts)
{
std::string out = "";
out = out + "{ ";
for (auto i : jnts) for (auto i : jnts)
std::cout << i << std::endl; out = out + std::to_string(i) + ", ";
out = out.substr(0, out.size()-2); //remove trailing comma
out = out + " }";
std::cout << out << std::endl;
} }
int main(int argc, char **argv) int main(int argc, char **argv)
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
std::string hw_ns = "ufactory"; std::string hw_ns = "ufactory";
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("lite6_calibration"); node = rclcpp::Node::make_shared("lite6_calibration");
int ret; int ret;
signal(SIGINT, exit_sig_handler); signal(SIGINT, exit_sig_handler);
@@ -42,7 +58,7 @@ int main(int argc, char **argv)
client.init(node, hw_ns); client.init(node, hw_ns);
client.motion_enable(true); client.motion_enable(true);
println("Setting xArm lite6 to free-drive mode. Attach pen and touch the drawing surface."); println("Setting xArm lite6 to free-drive mode. Attach pen and touch the drawing surface. (You can also skip this if you do not want to measure Z)");
client.set_mode(2); client.set_mode(2);
client.set_state(0); client.set_state(0);
//rclcpp::sleep_for(std::chrono::seconds(20)); //rclcpp::sleep_for(std::chrono::seconds(20));
@@ -55,52 +71,61 @@ int main(int argc, char **argv)
client.set_state(0); client.set_state(0);
rclcpp::sleep_for(std::chrono::seconds(2)); rclcpp::sleep_for(std::chrono::seconds(2));
std::vector<float> jnt_drawing_pose = {-0.813972, -0.0103697, 0.554617, 3.09979, -0.627334, -0.397301, 0}; //std::vector<float> jnt_drawing_pose = { -0.975004, 0.0734182, 0.443928, 3.14102, -0.370552, -0.85577, 0 };
std::vector<float> jnt_drawing_pose = { -0.975008, 0.00889134, 0.453255, 3.1414, -0.444295, -0.85692, 0 } ;
std::vector<float> jnt_pose = { 0, 0, 0, 0, 0, 0, 0 }; std::vector<float> jnt_pose = { 0, 0, 0, 0, 0, 0, 0 };
client.get_servo_angle(jnt_pose); client.get_servo_angle(jnt_pose);
println("Moving to start drawing pose");
//XArmROSClient::set_servo_angle(const std::vector<fp32>& angles, fp32 speed, fp32 acc, fp32 mvtime, bool wait, fp32 timeout, fp32 radius) print_joints(jnt_pose);
client.set_servo_angle(jnt_drawing_pose, 1, 1, 1, true, 100, -1);
//client.set_servo_angle_j(jnt_drawing_pose, 1, 1, 100); //client.set_servo_angle_j(jnt_drawing_pose, 1, 1, 100);
//rclcpp::sleep_for(std::chrono::seconds(5)); //rclcpp::sleep_for(std::chrono::seconds(5));
// Compute position of pen from joint state
robot_model_loader::RobotModelLoader robot_model_loader(node);
const moveit::core::RobotModelPtr& kinematic_model = robot_model_loader.getModel();
moveit::core::RobotStatePtr kinematic_state(new moveit::core::RobotState(kinematic_model));
const moveit::core::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(MOVE_GROUP);
std::string ee_link = "pen_link";
std::vector<double> jnts;
for (auto j : jnt_pose)
jnts.push_back(j);
jnts.resize(joint_model_group->getVariableNames().size());
kinematic_state->setJointGroupPositions(joint_model_group, jnts);
// from tutorial https://ros-planning.github.io/moveit_tutorials/doc/robot_model_and_robot_state/robot_model_and_robot_state_tutorial.html
// https://github.com/ros-planning/moveit_tutorials/blob/master/doc/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp
//robot_model_loader::RobotModelLoader robot_model_loader(node, "robot_description");
kinematic_state->setJointGroupPositions(joint_model_group, jnts);
// https://mycourses.aalto.fi/pluginfile.php/1433193/mod_resource/content/2/Intro_to_ROS_Eigen.pdf
const Eigen::Isometry3d& end_effector_state = kinematic_state->getGlobalLinkTransform(ee_link);
auto x = std::to_string(end_effector_state.translation().x());
auto y = std::to_string(end_effector_state.translation().y());
auto z = std::to_string(end_effector_state.translation().z());
//println("x for '" + ee_link + "': " + x);
//println("y for '" + ee_link + "': " + y);
println("z-offset value for '" + ee_link + "' (use this value for the current pen): " + z);
println("WARNING. Moving to start drawing pose. Press ctrl-c to cancel");
wait();
client.set_servo_angle(jnt_drawing_pose, 1, 1, 1, true, 100, -1);
client.set_mode(0); client.set_mode(0);
client.set_state(0); client.set_state(0);
return 0;
client.set_mode(4); rclcpp::shutdown();
client.set_state(0);
std::vector<float> jnt_v = { 1, 0, 0, 0, 0, 0, 0 };
ret = client.vc_set_joint_velocity(jnt_v);
RCLCPP_INFO(rclcpp::get_logger("test_xarm_velo_move"), "velo_move_joint: %d", ret);
rclcpp::sleep_for(std::chrono::seconds(2));
jnt_v[0] = -1;
ret = client.vc_set_joint_velocity(jnt_v);
RCLCPP_INFO(rclcpp::get_logger("test_xarm_velo_move"), "velo_move_joint: %d", ret);
rclcpp::sleep_for(std::chrono::seconds(2));
// stop
jnt_v[0] = 0;
ret = client.vc_set_joint_velocity(jnt_v);
RCLCPP_INFO(rclcpp::get_logger("test_xarm_velo_move"), "velo_move_joint: %d", ret);
std::vector<float> line_v = { 1, 0, 0, 0, 0, 0}; println("Done, ignore any errors after this. Restart lite6_controller after I exit.");
client.set_mode(5); wait();
client.set_state(0);
ret = client.vc_set_cartesian_velocity(line_v);
RCLCPP_INFO(rclcpp::get_logger("test_xarm_velo_move"), "velo_move_line: %d", ret);
rclcpp::sleep_for(std::chrono::seconds(2));
line_v[0] = -1;
ret = client.vc_set_cartesian_velocity(line_v);
RCLCPP_INFO(rclcpp::get_logger("test_xarm_velo_move"), "velo_move_line: %d", ret);
rclcpp::sleep_for(std::chrono::seconds(2));
// stop
line_v[0] = 0;
ret = client.vc_set_cartesian_velocity(line_v);
RCLCPP_INFO(rclcpp::get_logger("test_xarm_velo_move"), "velo_move_line: %d", ret);
RCLCPP_INFO(rclcpp::get_logger("test_xarm_velo_move"), "test_xarm_velo_move over");
return 0; return 0;
} }

View File

@@ -47,15 +47,6 @@ const std::string MOVE_GROUP = "lite6";
using namespace std::chrono_literals; using namespace std::chrono_literals;
// MOTION PLANNING API
// https://github.com/ros-planning/moveit2_tutorials/blob/humble/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp
// https://moveit.picknik.ai/humble/doc/examples/motion_planning_api/motion_planning_api_tutorial.html
// https://github.com/ros-planning/moveit2/blob/main/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_service.cpp
//
//
// USE
// https://industrial-training-master.readthedocs.io/en/foxy/_source/session4/ros2/0-Motion-Planning-CPP.html
/** /**
* Controller for xArm Lite6, implementing RobotController * Controller for xArm Lite6, implementing RobotController
*/ */
@@ -89,20 +80,9 @@ public:
float xlim_upper = 0.305; float xlim_upper = 0.305;
float ylim_lower = -0.1475; float ylim_lower = -0.1475;
float ylim_upper = 0.1475; float ylim_upper = 0.1475;
float zlim_lower = 0.1945; float zlim_lower = 0.141087;
float zlim_upper = 0.200; float zlim_upper = zlim_lower + 0.01;
//bool moved = false;
//
// TODO get pilz working
//std::unique_ptr<pilz_industrial_motion_planner::CommandListManager> command_list_manager_;
// command_list_manager_ = std::make_unique<pilz_industrial_motion_planner::CommandListManager>(this->move_group.getNodeHandle(), this->move_group.getRobotModel());
/**
* CommandListManager, used to plan MotionSequenceRequest
*/
//pilz_industrial_motion_planner::CommandListManager command_list_manager;
//pilz_industrial_motion_planner::CommandListManager command_list_manager(*std::shared_ptr<rclcpp::Node>(std::move(this)), this->move_group.getRobotModel());
/** /**
* Constructor * Constructor
@@ -110,24 +90,29 @@ public:
Lite6Controller(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()) Lite6Controller(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
: RobotController(options), : RobotController(options),
move_group(std::shared_ptr<rclcpp::Node>(std::move(this)), MOVE_GROUP) move_group(std::shared_ptr<rclcpp::Node>(std::move(this)), MOVE_GROUP)
//moveit_cpp_(std::shared_ptr<rclcpp::Node>(std::move(this))),
//planning_component_(MOVE_GROUP, moveit_cpp_),
//command_list_manager(std::shared_ptr<rclcpp::Node>(std::move(this)), this->move_group.getRobotModel())
{ {
// Declare parameters
this->declare_parameter("lite6_x_limit_lower", 0.1);
this->declare_parameter("lite6_x_limit_upper", 0.305);
this->declare_parameter("lite6_y_limit_lower", -0.1475);
this->declare_parameter("lite6_y_limit_upper", 0.1475);
this->declare_parameter("lite6_z_offset", 0.141087);
this->declare_parameter("lite6_z_lift_amount", 0.01);
this->declare_parameter("lite6_max_velocity_scaling_factor", 1.0);
this->declare_parameter("lite6_max_acceleration_scaling_factor", 0.6);
this->declare_parameter("lite6_blend_radius", 0.0);
xlim_lower = this->get_parameter("lite6_x_limit_lower").as_double();
xlim_upper = this->get_parameter("lite6_x_limit_upper").as_double();
ylim_lower = this->get_parameter("lite6_y_limit_lower").as_double();
ylim_upper = this->get_parameter("lite6_y_limit_upper").as_double();
zlim_lower = this->get_parameter("lite6_z_offset").as_double();
zlim_upper = zlim_lower + this->get_parameter("lite6_z_lift_amount").as_double();
//command_list_manager = new pilz_industrial_motion_planner::CommandListManager(this->move_group.getNodeHandle(), this->move_group.getRobotModel());
//command_list_manager = new pilz_industrial_motion_planner::CommandListManager(std::shared_ptr<rclcpp::Node>(std::move(this)), this->move_group.getRobotModel());
// Use upper joint velocity and acceleration limits
this->move_group.setMaxAccelerationScalingFactor(1.0); this->move_group.setMaxAccelerationScalingFactor(1.0);
//setting this lower seems to improve overall time and prevents robot from moving too fast
this->move_group.setMaxVelocityScalingFactor(1.0); this->move_group.setMaxVelocityScalingFactor(1.0);
//this->move_group.setMaxVelocityScalingFactor(0.8); //this->move_group.setMaxVelocityScalingFactor(0.8);
// 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));
//
trajectory_timer_ = this->create_wall_timer( trajectory_timer_ = this->create_wall_timer(
10ms, std::bind(&Lite6Controller::executeTrajectoryFromQueue, this)); 10ms, std::bind(&Lite6Controller::executeTrajectoryFromQueue, this));
@@ -135,18 +120,10 @@ public:
void setup() void setup()
{ {
//moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(move_group.getNodeHandle());
try try
{ {
//moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(this->shared_from_this());
//moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(move_group.getNodeHandle());
//planning_component_ = std::make_shared<moveit_cpp::PlanningComponent>(MOVE_GROUP, moveit_cpp_);
//
planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(this->shared_from_this(), planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(this->shared_from_this(),
"robot_description"); "robot_description");
//RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Getting initial robot state");
//move_group.startStateMonitor(5);
this->sequence_client_ = this->sequence_client_ =
this->create_client<moveit_msgs::srv::GetMotionSequence>("plan_sequence_path"); this->create_client<moveit_msgs::srv::GetMotionSequence>("plan_sequence_path");
@@ -217,11 +194,12 @@ public:
/** /**
* *
*/ */
moveit_msgs::msg::MotionSequenceRequest createMotionSequenceRequest(const std::vector<geometry_msgs::msg::PoseStamped> *path) moveit_msgs::msg::MotionSequenceRequest createMotionSequenceRequest(const std::vector<geometry_msgs::msg::PoseStamped> *path, std::string planner_id)
{ {
moveit_msgs::msg::MotionSequenceRequest msr = moveit_msgs::msg::MotionSequenceRequest(); moveit_msgs::msg::MotionSequenceRequest msr = moveit_msgs::msg::MotionSequenceRequest();
//waypoints.push_back(move_group.getCurrentPose().pose); //waypoints.push_back(move_group.getCurrentPose().pose);
std::string ee_link = move_group.getLinkNames().back(); //std::string ee_link = move_group.getLinkNames().back();
std::string ee_link = "pen_link";
RCLCPP_INFO(this->get_logger(), "Got ee_link: %s", ee_link.c_str()); RCLCPP_INFO(this->get_logger(), "Got ee_link: %s", ee_link.c_str());
geometry_msgs::msg::Point previous_point; geometry_msgs::msg::Point previous_point;
//previous_point.point.x = -1.0; //previous_point.point.x = -1.0;
@@ -233,15 +211,17 @@ public:
moveit_msgs::msg::MotionSequenceItem msi = moveit_msgs::msg::MotionSequenceItem(); moveit_msgs::msg::MotionSequenceItem msi = moveit_msgs::msg::MotionSequenceItem();
planning_interface::MotionPlanRequest mpr = planning_interface::MotionPlanRequest(); planning_interface::MotionPlanRequest mpr = planning_interface::MotionPlanRequest();
mpr.planner_id = planner_id;
//mpr.planner_id = "PTP"; //mpr.planner_id = "PTP";
mpr.planner_id = "LIN"; //mpr.planner_id = "LIN";
mpr.group_name = move_group.getName(); mpr.group_name = move_group.getName();
//mpr.max_velocity_scaling_factor = 1.0; //mpr.max_velocity_scaling_factor = 1.0;
mpr.max_velocity_scaling_factor = 0.3; mpr.max_velocity_scaling_factor = this->get_parameter("lite6_max_velocity_scaling_factor").as_double();
mpr.max_acceleration_scaling_factor = 0.4; mpr.max_acceleration_scaling_factor = this->get_parameter("lite6_max_acceleration_scaling_factor").as_double();
//mpr.max_acceleration_scaling_factor = 0.1; //mpr.max_acceleration_scaling_factor = 0.1;
mpr.allowed_planning_time = 10; mpr.allowed_planning_time = 20;
mpr.max_cartesian_speed = 3; // m/s //mpr.max_cartesian_speed = 2; // m/s
//mpr.goal_constraints.position_constraints.header.frame_id = "world"; //mpr.goal_constraints.position_constraints.header.frame_id = "world";
// A tolerance of 0.01 m is specified in position // A tolerance of 0.01 m is specified in position
@@ -270,9 +250,7 @@ public:
mpr.goal_constraints.push_back(pose_goal); mpr.goal_constraints.push_back(pose_goal);
msi.req = mpr; msi.req = mpr;
//msi.blend_radius = 6e-7; //TODO make configurable msi.blend_radius = this->get_parameter("lite6_blend_radius").as_double();
//msi.blend_radius = 0.000001; //TODO make configurable
msi.blend_radius = 0.0; //TODO make configurable
if (coincidentPoints(&pose.pose.position, &previous_point, msi.blend_radius + 1e-5)) if (coincidentPoints(&pose.pose.position, &previous_point, msi.blend_radius + 1e-5))
{ {
RCLCPP_ERROR(this->get_logger(), "Detected coincident points, setting blend radius to 0.0"); RCLCPP_ERROR(this->get_logger(), "Detected coincident points, setting blend radius to 0.0");
@@ -288,6 +266,7 @@ public:
msr.items.push_back(msi); msr.items.push_back(msi);
} }
msr.items.back().blend_radius = 0.0; // Last element blend must be 0 msr.items.back().blend_radius = 0.0; // Last element blend must be 0
moveit_msgs::msg::RobotState state_msg; moveit_msgs::msg::RobotState state_msg;
if (move_group_state == NULL) if (move_group_state == NULL)
{ {
@@ -299,6 +278,11 @@ public:
return msr; return msr;
} }
moveit_msgs::msg::MotionSequenceRequest createMotionSequenceRequest(const std::vector<geometry_msgs::msg::PoseStamped> *path)
{
return createMotionSequenceRequest(path, "LIN");
}
/** /**
* *
*/ */
@@ -402,8 +386,17 @@ public:
void executeTrajectoryFromQueue() void executeTrajectoryFromQueue()
{ {
if (busy || trajectory_queue.empty()) if (trajectory_queue.empty())
{
if (busy)
return;
busy = true;
//RCLCPP_INFO(this->get_logger(), "Getting robot state");
//move_group_state = move_group.getCurrentState(10);
busy = false;
return; return;
}
busy = true; busy = true;
RCLCPP_INFO(this->get_logger(), "Executing next trajectory from queue"); RCLCPP_INFO(this->get_logger(), "Executing next trajectory from queue");
move_group.execute(trajectory_queue.front()); move_group.execute(trajectory_queue.front());
@@ -411,6 +404,103 @@ public:
busy = false; busy = false;
} }
moveit_msgs::msg::RobotTrajectory sendRequest(moveit_msgs::msg::MotionSequenceRequest msr)
{
auto req = std::make_shared<moveit_msgs::srv::GetMotionSequence::Request>();
req->request = msr;
RCLCPP_INFO(this->get_logger(), "Sending request to sequence service");
auto res = sequence_client_->async_send_request(req);
auto ts = res.get()->response.planned_trajectories;
// Set move_group_state to the last state of planned trajectory (planning of next trajectory starts there)
if (ts.empty())
{
moveit_msgs::msg::RobotTrajectory t;
return t;
}
return ts[0];
}
void setMoveGroupState(moveit_msgs::msg::RobotTrajectory t)
{
if (t.joint_trajectory.points.empty())
{
RCLCPP_ERROR(this->get_logger(), "TRAJECTORY IS EMPTY");
return;
}
robot_trajectory::RobotTrajectory rt(move_group.getRobotModel());
rt.setRobotTrajectoryMsg(*move_group_state, t);
move_group_state = rt.getLastWayPointPtr();
}
void pathToTrajectory(const std::vector<geometry_msgs::msg::PoseStamped> *path, std::vector<moveit_msgs::msg::RobotTrajectory> *ts)
{
std::vector<geometry_msgs::msg::PoseStamped> penup = {};
std::vector<geometry_msgs::msg::PoseStamped> tail = {};
bool up = true;
if (!path)
{
RCLCPP_ERROR(this->get_logger(), "Received null pointer for path");
return;
}
for (auto p : *path)
{
if (p.pose.position.z > 0)
up = false;
if (up)
//penup->push_back(p);
penup.push_back(p);
else
{
up = false;
//tail->push_back(p);
tail.push_back(p);
}
}
if (!penup.empty())
{
auto msr = createMotionSequenceRequest(&penup, "PTP");
RCLCPP_ERROR(this->get_logger(), "Created MSR for penup");
if (msr.items.empty())
{
RCLCPP_ERROR(this->get_logger(), "MSR EMPTY");
return;
}
ts->push_back(sendRequest(msr));
//planAndLogOffset(&penup);
setMoveGroupState(ts->back());
}
else
{
RCLCPP_ERROR(this->get_logger(), "Penup path is empty, all motions will be LIN");
}
if (!tail.empty())
{
auto msr = createMotionSequenceRequest(&tail, "LIN");
RCLCPP_ERROR(this->get_logger(), "Created MSR for tail");
if (msr.items.empty())
{
RCLCPP_ERROR(this->get_logger(), "MSR EMPTY");
return;
}
ts->push_back(sendRequest(msr));
//planAndLogOffset(&tail);
setMoveGroupState(ts->back());
}
else
{
RCLCPP_ERROR(this->get_logger(), "Path was empty, no trajectories created");
}
}
/** /**
* Callback that executes path on robot * Callback that executes path on robot
*/ */
@@ -423,37 +513,33 @@ public:
auto feedback = std::make_shared<robot_interfaces::action::ExecuteMotion::Feedback>(); auto feedback = std::make_shared<robot_interfaces::action::ExecuteMotion::Feedback>();
auto result = std::make_shared<robot_interfaces::action::ExecuteMotion::Result>(); auto result = std::make_shared<robot_interfaces::action::ExecuteMotion::Result>();
auto msr = createMotionSequenceRequest(&goal->motion.path); std::vector<moveit_msgs::msg::RobotTrajectory> ts;
RCLCPP_INFO(this->get_logger(), "Created MSR"); pathToTrajectory(&goal->motion.path, &ts);
//planAndLogOffset(&goal->motion.path); long unsigned int n = 0;
RCLCPP_INFO(this->get_logger(), "Got %ld trajectories", ts.size());
for (auto t : ts)
{
RCLCPP_INFO(this->get_logger(), "Adding result to motion queue");
if (t.joint_trajectory.points.empty())
{
RCLCPP_ERROR(this->get_logger(), "TRAJECTORY IS EMPTY");
continue;
}
trajectory_queue.push(t);
n++;
}
RCLCPP_INFO(this->get_logger(), "Creating req");
auto req = std::make_shared<moveit_msgs::srv::GetMotionSequence::Request>();
RCLCPP_INFO(this->get_logger(), "Setting msr request");
req->request = msr;
RCLCPP_INFO(this->get_logger(), "Sending request to sequence service");
auto res = sequence_client_->async_send_request(req);
RCLCPP_INFO(this->get_logger(), "Waiting for result");
auto ts = res.get()->response.planned_trajectories;
std::string status = ""; std::string status = "";
if (ts.size() > 0) if (n == ts.size())
{ {
status = "success"; status = "success";
RCLCPP_INFO(this->get_logger(), "Got %ld trajectories", ts.size());
RCLCPP_INFO(this->get_logger(), "Adding result to motion queue");
trajectory_queue.push(ts[0]);
// Set move_group_state to the last state of planned trajectory (planning of next trajectory starts there)
robot_trajectory::RobotTrajectory rt(move_group.getRobotModel());
rt.setRobotTrajectoryMsg(*move_group_state, ts[0]);
move_group_state = rt.getLastWayPointPtr();
status = status + "," + pointsToString(&goal->motion.path,0,0,0); status = status + "," + pointsToString(&goal->motion.path,0,0,0);
appendLineToFile("OUTPUT.csv", status); appendLineToFile("OUTPUT.csv", status);
result->result = "success"; result->result = "success";
goal_handle->succeed(result); goal_handle->succeed(result);
RCLCPP_INFO(this->get_logger(), "Goal succeeded"); RCLCPP_INFO(this->get_logger(), "Goal succeeded");
return; return;

View File

@@ -23,7 +23,7 @@ class DummyController : public RobotController
virtual void executePath(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteMotion>> goal_handle) virtual void executePath(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteMotion>> goal_handle)
{ {
RCLCPP_INFO(this->get_logger(), "Executing goal"); RCLCPP_INFO(this->get_logger(), "Executing goal");
rclcpp::Rate loop_rate(20); rclcpp::Rate loop_rate(100);
const auto goal = goal_handle->get_goal(); const auto goal = goal_handle->get_goal();
auto feedback = std::make_shared<robot_interfaces::action::ExecuteMotion::Feedback>(); auto feedback = std::make_shared<robot_interfaces::action::ExecuteMotion::Feedback>();
auto result = std::make_shared<robot_interfaces::action::ExecuteMotion::Result>(); auto result = std::make_shared<robot_interfaces::action::ExecuteMotion::Result>();