Compare commits
18 Commits
async_traj
...
ef6d4a27be
| Author | SHA1 | Date | |
|---|---|---|---|
| ef6d4a27be | |||
| cb1923e56a | |||
| a9ab26aeed | |||
| 6910d06c2e | |||
| 360528808e | |||
| ba13618c95 | |||
| dc0445abca | |||
| 6c45716832 | |||
| 9e9ec2d3f9 | |||
| 6467d80bc0 | |||
| 1c02d8dce2 | |||
| 6d6f2aa393 | |||
| c5761dc8e8 | |||
| e771acd598 | |||
| 2aee36b333 | |||
| 1d11b96b49 | |||
| ef994440f4 | |||
| 2e28c4e99f |
32
README.md
32
README.md
@@ -34,6 +34,13 @@ 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.
|
||||||
|
``` sh
|
||||||
|
sudo bash .docker/build.bash
|
||||||
|
```
|
||||||
|
``` sh
|
||||||
|
sudo bash .docker/devel.bash
|
||||||
|
```
|
||||||
|
|
||||||
## TODO Building locally
|
## TODO Building locally
|
||||||
|
|
||||||
@@ -60,9 +67,11 @@ DummyController echoes Motion messages to the terminal.
|
|||||||
ros2 run robot_controller dummy_controller
|
ros2 run robot_controller dummy_controller
|
||||||
```
|
```
|
||||||
|
|
||||||
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.
|
||||||
|
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
|
ros2 launch axidraw_controller axidraw_controller.launch.py serial_port:=/dev/ttyACM0
|
||||||
```
|
```
|
||||||
|
|
||||||
This starts the simulated lite6
|
This starts the simulated lite6
|
||||||
@@ -87,6 +96,23 @@ ros2 run drawing_controller drawing_controller svg/test.svg
|
|||||||
```
|
```
|
||||||
This will draw the svg image given as the last argument.
|
This will draw the svg image given as the last argument.
|
||||||
|
|
||||||
|
### tmux workflow
|
||||||
|
lite6 interface: http://192.168.1.150:18333
|
||||||
|
|
||||||
|
#### Raspberry pi
|
||||||
|
On the raspberry pi run
|
||||||
|
``` sh
|
||||||
|
./setup_ros.sh
|
||||||
|
```
|
||||||
|
This will open a tmux session with the necessary ros2 packages sourced.
|
||||||
|
#### Docker container
|
||||||
|
``` sh
|
||||||
|
tmux
|
||||||
|
```
|
||||||
|
|
||||||
|
If actively
|
||||||
|
|
||||||
|
|
||||||
## SVG compatibility info
|
## SVG compatibility info
|
||||||
Tested with SVG from the following programs
|
Tested with SVG from the following programs
|
||||||
- Inkscape
|
- Inkscape
|
||||||
@@ -177,7 +203,7 @@ And the following SVG path commands are supported:
|
|||||||
| MoveTo | M, m | |
|
| MoveTo | M, m | |
|
||||||
| LineTo | L, l, H, h, V, v | |
|
| LineTo | L, l, H, h, V, v | |
|
||||||
| Cubic Bézier Curve | C, c, S, s | |
|
| Cubic Bézier Curve | C, c, S, s | |
|
||||||
| Quadratic Bézier Curve | | Q, q, T, t |
|
| Quadratic Bézier Curve | Q, q | T, t |
|
||||||
| Elliptical Arc Curve | | A, a |
|
| Elliptical Arc Curve | | A, a |
|
||||||
| ClosePath | Z, z | |
|
| ClosePath | Z, z | |
|
||||||
|
|
||||||
|
|||||||
@@ -162,7 +162,7 @@ class AxidrawController : public RobotController
|
|||||||
this->penup_pub->publish(std_msgs::msg::Empty());
|
this->penup_pub->publish(std_msgs::msg::Empty());
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
this->pendown_pub->publish(std_msgs::msg::Empty());
|
//this->pendown_pub->publish(std_msgs::msg::Empty());
|
||||||
while (i + count + 1 < points.size() && points[i + count + 1].z <= 0)
|
while (i + count + 1 < points.size() && points[i + count + 1].z <= 0)
|
||||||
{
|
{
|
||||||
count++;
|
count++;
|
||||||
|
|||||||
@@ -42,6 +42,7 @@ class AxidrawSerial(Node):
|
|||||||
status = {
|
status = {
|
||||||
"serial": "not ready",
|
"serial": "not ready",
|
||||||
"motion": "waiting",
|
"motion": "waiting",
|
||||||
|
"pen": "up",
|
||||||
}
|
}
|
||||||
|
|
||||||
def init_serial(self, port):
|
def init_serial(self, port):
|
||||||
@@ -60,9 +61,15 @@ 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.accel = 100 # 100% speed
|
||||||
|
self.ad.options.pen_rate_lower = 100 # 100% speed
|
||||||
|
self.ad.options.pen_rate_raise = 100 # 100% speed
|
||||||
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"
|
||||||
|
self.status["pen"] = "up"
|
||||||
return True
|
return True
|
||||||
|
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
@@ -83,7 +90,8 @@ class AxidrawSerial(Node):
|
|||||||
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):
|
||||||
self.get_logger().error("Failed to connect to axidraw on port:{}".format(port))
|
self.get_logger().error("Failed to connect to axidraw on port:{}, retrying".format(port))
|
||||||
|
self.get_logger().info("Successfully connected to axidraw on port:{}".format(port))
|
||||||
|
|
||||||
self.move_sub = self.create_subscription(Point, 'axidraw_move', self.move_callback, qos_profile=QoSProfile(depth=1))
|
self.move_sub = self.create_subscription(Point, 'axidraw_move', self.move_callback, qos_profile=QoSProfile(depth=1))
|
||||||
self.penup_sub = self.create_subscription(Empty, 'axidraw_penup', self.penup_callback, qos_profile=QoSProfile(depth=1))
|
self.penup_sub = self.create_subscription(Empty, 'axidraw_penup', self.penup_callback, qos_profile=QoSProfile(depth=1))
|
||||||
@@ -165,7 +173,9 @@ class AxidrawSerial(Node):
|
|||||||
|
|
||||||
self.get_logger().info("Received penup: {}".format(msg))
|
self.get_logger().info("Received penup: {}".format(msg))
|
||||||
|
|
||||||
|
if self.status['pen'] == "down":
|
||||||
self.ad.penup()
|
self.ad.penup()
|
||||||
|
self.status['pen'] = "up"
|
||||||
self.set_ready()
|
self.set_ready()
|
||||||
|
|
||||||
def pendown_callback(self, msg):
|
def pendown_callback(self, msg):
|
||||||
@@ -178,7 +188,9 @@ class AxidrawSerial(Node):
|
|||||||
|
|
||||||
self.get_logger().info("Received pendown: {}".format(msg))
|
self.get_logger().info("Received pendown: {}".format(msg))
|
||||||
|
|
||||||
|
if self.status['pen'] == "up":
|
||||||
self.ad.pendown()
|
self.ad.pendown()
|
||||||
|
self.status['pen'] = "down"
|
||||||
self.set_ready()
|
self.set_ready()
|
||||||
|
|
||||||
def stroke_callback(self, msg):
|
def stroke_callback(self, msg):
|
||||||
@@ -193,6 +205,7 @@ class AxidrawSerial(Node):
|
|||||||
|
|
||||||
path = [ [p.x,p.y] for p in msg.points ]
|
path = [ [p.x,p.y] for p in msg.points ]
|
||||||
self.ad.draw_path(path)
|
self.ad.draw_path(path)
|
||||||
|
self.status['pen'] = "up"
|
||||||
self.set_ready()
|
self.set_ready()
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,5 @@
|
|||||||
|
cartesian_limits:
|
||||||
|
max_trans_vel: 2.0
|
||||||
|
max_trans_acc: 3.00
|
||||||
|
max_trans_dec: -5.0
|
||||||
|
max_rot_vel: 1.57
|
||||||
@@ -4,31 +4,31 @@
|
|||||||
joint_limits:
|
joint_limits:
|
||||||
joint1:
|
joint1:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 2.14
|
max_velocity: 10.14
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 1.0
|
max_acceleration: 20.0
|
||||||
joint2:
|
joint2:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 2.14
|
max_velocity: 10.14
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 1.0
|
max_acceleration: 20.0
|
||||||
joint3:
|
joint3:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 2.14
|
max_velocity: 10.14
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 1.0
|
max_acceleration: 20.0
|
||||||
joint4:
|
joint4:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 2.14
|
max_velocity: 10.14
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 1.0
|
max_acceleration: 20.0
|
||||||
joint5:
|
joint5:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 2.14
|
max_velocity: 10.14
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 1.0
|
max_acceleration: 20.0
|
||||||
joint6:
|
joint6:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 2.14
|
max_velocity: 10.14
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 1.0
|
max_acceleration: 20.0
|
||||||
|
|||||||
@@ -65,19 +65,22 @@ def add_prefix_to_moveit_params(controllers_yaml=None, ompl_planning_yaml=None,
|
|||||||
|
|
||||||
|
|
||||||
def get_xarm_robot_description_parameters(
|
def get_xarm_robot_description_parameters(
|
||||||
xacro_urdf_file=PathJoinSubstitution([FindPackageShare('xarm_description'), 'urdf', 'xarm_device.urdf.xacro']),
|
xacro_urdf_file=PathJoinSubstitution([FindPackageShare('custom_xarm_description'), 'urdf', 'xarm_device.urdf.xacro']),
|
||||||
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
|
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('custom_xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
|
||||||
urdf_arguments={},
|
urdf_arguments={},
|
||||||
srdf_arguments={},
|
srdf_arguments={},
|
||||||
arguments={}):
|
arguments={}):
|
||||||
urdf_arguments['ros2_control_plugin'] = urdf_arguments.get('ros2_control_plugin', 'uf_robot_hardware/UFRobotSystemHardware')
|
urdf_arguments['ros2_control_plugin'] = urdf_arguments.get('ros2_control_plugin', 'uf_robot_hardware/UFRobotSystemHardware')
|
||||||
moveit_config_package_name = 'xarm_moveit_config'
|
moveit_config_package_name = 'custom_xarm_moveit_config'
|
||||||
xarm_type = arguments.get('xarm_type', None)
|
xarm_type = arguments.get('xarm_type', None)
|
||||||
|
|
||||||
# xarm_description/launch/lib/robot_description_lib.py
|
# xarm_description/launch/lib/robot_description_lib.py
|
||||||
mod = load_python_launch_file_as_module(os.path.join(get_package_share_directory('xarm_description'), 'launch', 'lib', 'robot_description_lib.py'))
|
mod = load_python_launch_file_as_module(os.path.join(get_package_share_directory('custom_xarm_description'), 'launch', 'lib', 'robot_description_lib.py'))
|
||||||
get_xacro_file_content = getattr(mod, 'get_xacro_file_content')
|
get_xacro_file_content = getattr(mod, 'get_xacro_file_content')
|
||||||
|
|
||||||
|
joint_limits = load_yaml(moveit_config_package_name, 'config', xarm_type, 'joint_limits.yaml')
|
||||||
|
cartesian_limits = load_yaml(moveit_config_package_name, 'config', xarm_type, 'cartesian_limits.yaml')
|
||||||
|
joint_limits['cartesian_limits'] = cartesian_limits['cartesian_limits']
|
||||||
return {
|
return {
|
||||||
'robot_description': get_xacro_file_content(
|
'robot_description': get_xacro_file_content(
|
||||||
xacro_file=xacro_urdf_file,
|
xacro_file=xacro_urdf_file,
|
||||||
@@ -87,6 +90,6 @@ def get_xarm_robot_description_parameters(
|
|||||||
xacro_file=xacro_srdf_file,
|
xacro_file=xacro_srdf_file,
|
||||||
arguments=srdf_arguments
|
arguments=srdf_arguments
|
||||||
),
|
),
|
||||||
'robot_description_planning': load_yaml(moveit_config_package_name, 'config', xarm_type, 'joint_limits.yaml'),
|
'robot_description_planning': joint_limits,
|
||||||
'robot_description_kinematics': load_yaml(moveit_config_package_name, 'config', xarm_type, 'kinematics.yaml')
|
'robot_description_kinematics': load_yaml(moveit_config_package_name, 'config', xarm_type, 'kinematics.yaml')
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -114,13 +114,13 @@ class SVGPathParser():
|
|||||||
#print('inpput', control_points)
|
#print('inpput', control_points)
|
||||||
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 = 50
|
n = 500
|
||||||
curve = cf.cubic_curve(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)
|
||||||
coordinates = np.nan_to_num(coordinates)
|
coordinates = np.nan_to_num(coordinates)
|
||||||
coordinates = coordinates * maxval #denormalize values
|
#coordinates = coordinates * maxval #denormalize values
|
||||||
coordinates = dropzeros(coordinates)
|
coordinates = dropzeros(coordinates)
|
||||||
#self.logger.info("Appending curve points: {}".format(coordinates))
|
#self.logger.info("Appending curve points: {}".format(coordinates))
|
||||||
#print(coordinates)
|
#print(coordinates)
|
||||||
@@ -136,6 +136,20 @@ class SVGPathParser():
|
|||||||
x = coordinates[-1][0]
|
x = coordinates[-1][0]
|
||||||
y = coordinates[-1][1]
|
y = coordinates[-1][1]
|
||||||
return coordinates
|
return coordinates
|
||||||
|
def quadratic_bezier(control_points):
|
||||||
|
nonlocal x
|
||||||
|
nonlocal y
|
||||||
|
control_points = np.array(control_points)
|
||||||
|
n = 500
|
||||||
|
curve = cf.bezier(control_points, quadratic=True)
|
||||||
|
lin = np.linspace(curve.start(0), curve.end(0), n)
|
||||||
|
coordinates = curve(lin)
|
||||||
|
coordinates = np.nan_to_num(coordinates)
|
||||||
|
coordinates = dropzeros(coordinates)
|
||||||
|
if len(coordinates) > 0:
|
||||||
|
x = coordinates[-1][0]
|
||||||
|
y = coordinates[-1][1]
|
||||||
|
return coordinates
|
||||||
|
|
||||||
while i < len(path):
|
while i < len(path):
|
||||||
w = path[i]
|
w = path[i]
|
||||||
@@ -208,7 +222,6 @@ class SVGPathParser():
|
|||||||
# Cubic Bézier Curve commands
|
# Cubic Bézier Curve commands
|
||||||
if (w == "C"):
|
if (w == "C"):
|
||||||
while True:
|
while True:
|
||||||
# https://github.com/sintef/Splipy/tree/master/examples
|
|
||||||
control_points = [(x,y),
|
control_points = [(x,y),
|
||||||
(getnum(),getnum()),
|
(getnum(),getnum()),
|
||||||
(getnum(),getnum()),
|
(getnum(),getnum()),
|
||||||
@@ -221,7 +234,6 @@ class SVGPathParser():
|
|||||||
continue
|
continue
|
||||||
if (w == "c"):
|
if (w == "c"):
|
||||||
while True:
|
while True:
|
||||||
# https://github.com/sintef/Splipy/tree/master/examples
|
|
||||||
control_points = [(x,y),
|
control_points = [(x,y),
|
||||||
(x + getnum(), y + getnum()),
|
(x + getnum(), y + getnum()),
|
||||||
(x + getnum(), y + getnum()),
|
(x + getnum(), y + getnum()),
|
||||||
@@ -238,9 +250,27 @@ class SVGPathParser():
|
|||||||
self.logger.error("SVG path parser '{}' not implemented".format(w))
|
self.logger.error("SVG path parser '{}' not implemented".format(w))
|
||||||
# Quadratic Bézier Curve commands
|
# Quadratic Bézier Curve commands
|
||||||
if (w == "Q"):
|
if (w == "Q"):
|
||||||
self.logger.error("SVG path parser '{}' not implemented".format(w))
|
while True:
|
||||||
|
control_points = [(x,y),
|
||||||
|
(getnum(),getnum()),
|
||||||
|
(getnum(),getnum())]
|
||||||
|
coordinates = quadratic_bezier(control_points)
|
||||||
|
appendpoints(coordinates)
|
||||||
|
if not nextisnum():
|
||||||
|
break
|
||||||
|
i += 1
|
||||||
|
continue
|
||||||
if (w == "q"):
|
if (w == "q"):
|
||||||
self.logger.error("SVG path parser '{}' not implemented".format(w))
|
while True:
|
||||||
|
control_points = [(x,y),
|
||||||
|
(x + getnum(), y + getnum()),
|
||||||
|
(x + getnum(), y + getnum())]
|
||||||
|
coordinates = quadratic_bezier(control_points)
|
||||||
|
appendpoints(coordinates)
|
||||||
|
if not nextisnum():
|
||||||
|
break
|
||||||
|
i += 1
|
||||||
|
continue
|
||||||
if (w == "T"):
|
if (w == "T"):
|
||||||
self.logger.error("SVG path parser '{}' not implemented".format(w))
|
self.logger.error("SVG path parser '{}' not implemented".format(w))
|
||||||
if (w == "t"):
|
if (w == "t"):
|
||||||
|
|||||||
@@ -174,7 +174,7 @@ class SVGProcessor():
|
|||||||
def remove_redundant(self, motion):
|
def remove_redundant(self, motion):
|
||||||
# Remove points that are too close to the previous point, specified by the tolerance
|
# Remove points that are too close to the previous point, specified by the tolerance
|
||||||
mm = []
|
mm = []
|
||||||
tolerance = 0.001
|
tolerance = 0.0001
|
||||||
prev = (-1, -1, 0)
|
prev = (-1, -1, 0)
|
||||||
for i, p in enumerate(motion):
|
for i, p in enumerate(motion):
|
||||||
x = p[0]
|
x = p[0]
|
||||||
@@ -198,7 +198,7 @@ class SVGProcessor():
|
|||||||
"""
|
"""
|
||||||
# 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.009
|
||||||
epsilon = 0.005
|
epsilon = 0.0005
|
||||||
|
|
||||||
tmp = []
|
tmp = []
|
||||||
out = []
|
out = []
|
||||||
@@ -215,6 +215,7 @@ class SVGProcessor():
|
|||||||
tmp.append(list(p)[:-1])
|
tmp.append(list(p)[:-1])
|
||||||
lastup = penup
|
lastup = penup
|
||||||
|
|
||||||
|
# Handle anything left in tmp
|
||||||
if (len(tmp) > 0):
|
if (len(tmp) > 0):
|
||||||
out += sf(tmp)
|
out += sf(tmp)
|
||||||
|
|
||||||
|
|||||||
@@ -16,6 +16,8 @@ find_package(moveit REQUIRED)
|
|||||||
find_package(pilz_industrial_motion_planner REQUIRED)
|
find_package(pilz_industrial_motion_planner REQUIRED)
|
||||||
find_package(moveit_msgs REQUIRED)
|
find_package(moveit_msgs REQUIRED)
|
||||||
find_package(geometry_msgs REQUIRED)
|
find_package(geometry_msgs REQUIRED)
|
||||||
|
find_package(xarm_api REQUIRED)
|
||||||
|
find_package(xarm_msgs REQUIRED)
|
||||||
|
|
||||||
find_package(tf2_ros REQUIRED)
|
find_package(tf2_ros REQUIRED)
|
||||||
find_package(geometry_msgs REQUIRED)
|
find_package(geometry_msgs REQUIRED)
|
||||||
@@ -45,6 +47,19 @@ ament_target_dependencies(lite6_controller
|
|||||||
"moveit_ros_planning_interface"
|
"moveit_ros_planning_interface"
|
||||||
"robot_interfaces")
|
"robot_interfaces")
|
||||||
|
|
||||||
|
add_executable(lite6_calibration src/lite6_calibration.cpp)
|
||||||
|
ament_target_dependencies(lite6_calibration
|
||||||
|
"xarm_msgs"
|
||||||
|
"xarm_api"
|
||||||
|
"rclcpp"
|
||||||
|
"moveit"
|
||||||
|
"rclcpp_action"
|
||||||
|
"Eigen3"
|
||||||
|
"pilz_industrial_motion_planner"
|
||||||
|
"robot_controller"
|
||||||
|
"moveit_ros_planning_interface"
|
||||||
|
"robot_interfaces")
|
||||||
|
|
||||||
if(BUILD_TESTING)
|
if(BUILD_TESTING)
|
||||||
find_package(ament_lint_auto REQUIRED)
|
find_package(ament_lint_auto REQUIRED)
|
||||||
ament_lint_auto_find_test_dependencies()
|
ament_lint_auto_find_test_dependencies()
|
||||||
@@ -52,6 +67,7 @@ endif()
|
|||||||
|
|
||||||
install(TARGETS
|
install(TARGETS
|
||||||
lite6_controller
|
lite6_controller
|
||||||
|
lite6_calibration
|
||||||
DESTINATION lib/${PROJECT_NAME})
|
DESTINATION lib/${PROJECT_NAME})
|
||||||
|
|
||||||
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
|
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
|
||||||
|
|||||||
@@ -17,7 +17,7 @@ from launch.actions import OpaqueFunction
|
|||||||
def launch_setup(context, *args, **kwargs):
|
def launch_setup(context, *args, **kwargs):
|
||||||
use_sim_time = LaunchConfiguration("use_sim_time", default=True)
|
use_sim_time = LaunchConfiguration("use_sim_time", default=True)
|
||||||
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("draw_svg"), "rviz", "ign_moveit2_examples.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')
|
||||||
@@ -263,10 +263,14 @@ 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)
|
||||||
|
|
||||||
|
#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']
|
||||||
|
#input(joint_limits_yaml)
|
||||||
|
|
||||||
# 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
|
||||||
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.0
|
# joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.0
|
||||||
|
|
||||||
kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin'
|
kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin'
|
||||||
#kinematics_yaml['kinematics_solver'] = 'lma_kinematics_plugin/LMAKinematicsPlugin'
|
#kinematics_yaml['kinematics_solver'] = 'lma_kinematics_plugin/LMAKinematicsPlugin'
|
||||||
@@ -300,12 +304,8 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
prefix=prefix.perform(context))
|
prefix=prefix.perform(context))
|
||||||
|
|
||||||
|
|
||||||
robot_description_parameters['cartesian_limits'] = {}
|
#cartesian_limits = load_yaml(moveit_config_package_name, 'config', xarm_type, 'cartesian_limits.yaml')
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_vel'] = 1
|
#robot_description_parameters['robot_description_planning']['cartesian_limits'] = cartesian_limits['cartesian_limits']
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_acc'] = 2.25
|
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_dec'] = -5
|
|
||||||
robot_description_parameters['cartesian_limits']['max_rot_vel'] = 1.57
|
|
||||||
|
|
||||||
|
|
||||||
# Planning pipeline
|
# Planning pipeline
|
||||||
# https://github.com/AndrejOrsula/panda_moveit2_config/blob/master/launch/move_group_fake_control.launch.py
|
# https://github.com/AndrejOrsula/panda_moveit2_config/blob/master/launch/move_group_fake_control.launch.py
|
||||||
|
|||||||
@@ -75,7 +75,7 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
# robot description launch
|
# robot description launch
|
||||||
# xarm_description/launch/_robot_description.launch.py
|
# xarm_description/launch/_robot_description.launch.py
|
||||||
robot_description_launch = IncludeLaunchDescription(
|
robot_description_launch = IncludeLaunchDescription(
|
||||||
PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('xarm_description'), 'launch', '_robot_description.launch.py'])),
|
PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('custom_xarm_description'), 'launch', '_robot_description.launch.py'])),
|
||||||
launch_arguments={
|
launch_arguments={
|
||||||
'prefix': prefix,
|
'prefix': prefix,
|
||||||
'hw_ns': hw_ns,
|
'hw_ns': hw_ns,
|
||||||
@@ -105,12 +105,12 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
|
|
||||||
# robot_description_parameters
|
# robot_description_parameters
|
||||||
# xarm_moveit_config/launch/lib/robot_moveit_config_lib.py
|
# xarm_moveit_config/launch/lib/robot_moveit_config_lib.py
|
||||||
moveit_config_package_name = 'xarm_moveit_config'
|
moveit_config_package_name = 'custom_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'))
|
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')
|
get_xarm_robot_description_parameters = getattr(mod, 'get_xarm_robot_description_parameters')
|
||||||
robot_description_parameters = 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_urdf_file=PathJoinSubstitution([FindPackageShare('custom_xarm_description'), 'urdf', 'xarm_device.urdf.xacro']),
|
||||||
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
|
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('custom_xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
|
||||||
urdf_arguments={
|
urdf_arguments={
|
||||||
'prefix': prefix,
|
'prefix': prefix,
|
||||||
'hw_ns': hw_ns.perform(context).strip('/'),
|
'hw_ns': hw_ns.perform(context).strip('/'),
|
||||||
@@ -154,17 +154,12 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
ompl_planning_yaml = load_yaml(moveit_config_package_name, 'config', xarm_type, 'ompl_planning.yaml')
|
ompl_planning_yaml = load_yaml(moveit_config_package_name, 'config', xarm_type, 'ompl_planning.yaml')
|
||||||
kinematics_yaml = robot_description_parameters['robot_description_kinematics']
|
kinematics_yaml = robot_description_parameters['robot_description_kinematics']
|
||||||
|
|
||||||
robot_description_parameters['cartesian_limits'] = {}
|
kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin'
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_vel'] = 1
|
kinematics_yaml['kinematics_solver_search_resolution'] = 0.005
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_acc'] = 2.25
|
kinematics_yaml['kinematics_solver_timeout'] = 0.005
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_dec'] = -5
|
kinematics_yaml['kinematics_solver_attempts'] = 3
|
||||||
robot_description_parameters['cartesian_limits']['max_rot_vel'] = 1.57
|
|
||||||
|
|
||||||
#kinematics_yaml['kinematics_solver'] = 'kdl_kinematics_plugin/KDLKinematicsPlugin'
|
|
||||||
#kinematics_yaml['kinematics_solver_search_resolution'] = 0.005
|
|
||||||
#kinematics_yaml['kinematics_solver_timeout'] = 0.005
|
|
||||||
#kinematics_yaml['kinematics_solver_attempts'] = 3
|
|
||||||
kinematics_yaml['kinematics_solver_timeout'] = 10.0
|
kinematics_yaml['kinematics_solver_timeout'] = 10.0
|
||||||
|
|
||||||
kinematics_yaml['kinematics_solver_attempts'] = 10
|
kinematics_yaml['kinematics_solver_attempts'] = 10
|
||||||
|
|
||||||
joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None)
|
joint_limits_yaml = robot_description_parameters.get('robot_description_planning', None)
|
||||||
@@ -186,11 +181,11 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
joint_limits_yaml['joint_limits'].update(gripper_joint_limits_yaml['joint_limits'])
|
joint_limits_yaml['joint_limits'].update(gripper_joint_limits_yaml['joint_limits'])
|
||||||
|
|
||||||
# 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
|
||||||
#joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.5
|
# #joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.5
|
||||||
#joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 2.5
|
# #joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 2.5
|
||||||
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 3.0
|
# joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 3.0
|
||||||
|
|
||||||
add_prefix_to_moveit_params = getattr(mod, 'add_prefix_to_moveit_params')
|
add_prefix_to_moveit_params = getattr(mod, 'add_prefix_to_moveit_params')
|
||||||
add_prefix_to_moveit_params(
|
add_prefix_to_moveit_params(
|
||||||
@@ -249,7 +244,8 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
'planning_plugin': 'pilz_industrial_motion_planner/CommandPlanner',
|
'planning_plugin': 'pilz_industrial_motion_planner/CommandPlanner',
|
||||||
#'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""",
|
#'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""",
|
||||||
'request_adapters': """default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""",
|
'request_adapters': """default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""",
|
||||||
"default_planner_config": "PTP",
|
#"default_planner_config": "PTP",
|
||||||
|
"default_planner_config": "LIN",
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -264,6 +260,7 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
output='screen',
|
output='screen',
|
||||||
parameters=[
|
parameters=[
|
||||||
robot_description_parameters,
|
robot_description_parameters,
|
||||||
|
#cartesian_limits,
|
||||||
#ompl_planning_pipeline_config,
|
#ompl_planning_pipeline_config,
|
||||||
pilz_planning_pipeline_config,
|
pilz_planning_pipeline_config,
|
||||||
move_group_capabilities,
|
move_group_capabilities,
|
||||||
|
|||||||
@@ -75,7 +75,7 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
# robot description launch
|
# robot description launch
|
||||||
# xarm_description/launch/_robot_description.launch.py
|
# xarm_description/launch/_robot_description.launch.py
|
||||||
robot_description_launch = IncludeLaunchDescription(
|
robot_description_launch = IncludeLaunchDescription(
|
||||||
PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('xarm_description'), 'launch', '_robot_description.launch.py'])),
|
PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare('custom_xarm_description'), 'launch', '_robot_description.launch.py'])),
|
||||||
launch_arguments={
|
launch_arguments={
|
||||||
'prefix': prefix,
|
'prefix': prefix,
|
||||||
'hw_ns': hw_ns,
|
'hw_ns': hw_ns,
|
||||||
@@ -105,12 +105,12 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
|
|
||||||
# robot_description_parameters
|
# robot_description_parameters
|
||||||
# xarm_moveit_config/launch/lib/robot_moveit_config_lib.py
|
# xarm_moveit_config/launch/lib/robot_moveit_config_lib.py
|
||||||
moveit_config_package_name = 'xarm_moveit_config'
|
moveit_config_package_name = 'custom_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'))
|
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')
|
get_xarm_robot_description_parameters = getattr(mod, 'get_xarm_robot_description_parameters')
|
||||||
robot_description_parameters = 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_urdf_file=PathJoinSubstitution([FindPackageShare('custom_xarm_description'), 'urdf', 'xarm_device.urdf.xacro']),
|
||||||
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
|
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('custom_xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
|
||||||
urdf_arguments={
|
urdf_arguments={
|
||||||
'prefix': prefix,
|
'prefix': prefix,
|
||||||
'hw_ns': hw_ns.perform(context).strip('/'),
|
'hw_ns': hw_ns.perform(context).strip('/'),
|
||||||
@@ -156,9 +156,9 @@ 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)
|
||||||
|
|
||||||
# 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
|
||||||
joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.0
|
# joint_limits_yaml['joint_limits']['joint{}'.format(i)]['max_acceleration'] = 1.0
|
||||||
|
|
||||||
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)))
|
||||||
@@ -182,11 +182,8 @@ def launch_setup(context, *args, **kwargs):
|
|||||||
kinematics_yaml=kinematics_yaml, joint_limits_yaml=joint_limits_yaml,
|
kinematics_yaml=kinematics_yaml, joint_limits_yaml=joint_limits_yaml,
|
||||||
prefix=prefix.perform(context))
|
prefix=prefix.perform(context))
|
||||||
|
|
||||||
robot_description_parameters['cartesian_limits'] = {}
|
#cartesian_limits = load_yaml(moveit_config_package_name, 'config', xarm_type, 'cartesian_limits.yaml')
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_vel'] = 1
|
#robot_description_parameters['robot_description_planning']['cartesian_limits'] = cartesian_limits['cartesian_limits']
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_acc'] = 2.25
|
|
||||||
robot_description_parameters['cartesian_limits']['max_trans_dec'] = -5
|
|
||||||
robot_description_parameters['cartesian_limits']['max_rot_vel'] = 1.57
|
|
||||||
|
|
||||||
# Planning Configuration
|
# Planning Configuration
|
||||||
ompl_planning_pipeline_config = {
|
ompl_planning_pipeline_config = {
|
||||||
|
|||||||
@@ -15,6 +15,8 @@
|
|||||||
<!-- <depend>robot_controller</depend> -->
|
<!-- <depend>robot_controller</depend> -->
|
||||||
<depend>moveit</depend>
|
<depend>moveit</depend>
|
||||||
<depend>moveit_msgs</depend>
|
<depend>moveit_msgs</depend>
|
||||||
|
<depend>xarm_msgs</depend>
|
||||||
|
<depend>xarm_api</depend>
|
||||||
<depend>geometry_msgs</depend>
|
<depend>geometry_msgs</depend>
|
||||||
<depend>moveit_ros_planning_interface</depend>
|
<depend>moveit_ros_planning_interface</depend>
|
||||||
<depend>tf2_ros</depend>
|
<depend>tf2_ros</depend>
|
||||||
|
|||||||
106
src/lite6_controller/src/lite6_calibration.cpp
Normal file
106
src/lite6_controller/src/lite6_calibration.cpp
Normal file
@@ -0,0 +1,106 @@
|
|||||||
|
#include <signal.h>
|
||||||
|
#include <chrono>
|
||||||
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
#include <xarm_api/xarm_ros_client.h>
|
||||||
|
#include <iostream>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
|
||||||
|
void exit_sig_handler(int signum)
|
||||||
|
{
|
||||||
|
fprintf(stderr, "[lite6_calibration] Ctrl-C caught, exit process...\n");
|
||||||
|
exit(-1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void wait()
|
||||||
|
{
|
||||||
|
do
|
||||||
|
{
|
||||||
|
std::cout << '\n' << "Press a key to continue...";
|
||||||
|
} while (std::cin.get() != '\n');
|
||||||
|
}
|
||||||
|
|
||||||
|
void println(std::string s) {
|
||||||
|
std::cout << s << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_joints(std::vector<float> jnts) {
|
||||||
|
for (auto i : jnts)
|
||||||
|
std::cout << i << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
std::string hw_ns = "ufactory";
|
||||||
|
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("lite6_calibration");
|
||||||
|
int ret;
|
||||||
|
|
||||||
|
signal(SIGINT, exit_sig_handler);
|
||||||
|
|
||||||
|
xarm_api::XArmROSClient client;
|
||||||
|
client.init(node, hw_ns);
|
||||||
|
client.motion_enable(true);
|
||||||
|
|
||||||
|
println("Setting xArm lite6 to free-drive mode. Attach pen and touch the drawing surface.");
|
||||||
|
client.set_mode(2);
|
||||||
|
client.set_state(0);
|
||||||
|
//rclcpp::sleep_for(std::chrono::seconds(20));
|
||||||
|
wait();
|
||||||
|
//client.set_mode(0);
|
||||||
|
//client.set_state(0);
|
||||||
|
//rclcpp::sleep_for(std::chrono::seconds(2));
|
||||||
|
|
||||||
|
client.set_mode(0);
|
||||||
|
client.set_state(0);
|
||||||
|
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_pose = { 0, 0, 0, 0, 0, 0, 0 };
|
||||||
|
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)
|
||||||
|
client.set_servo_angle(jnt_drawing_pose, 1, 1, 1, true, 100, -1);
|
||||||
|
//client.set_servo_angle_j(jnt_drawing_pose, 1, 1, 100);
|
||||||
|
//rclcpp::sleep_for(std::chrono::seconds(5));
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
client.set_mode(0);
|
||||||
|
client.set_state(0);
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
client.set_mode(4);
|
||||||
|
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};
|
||||||
|
client.set_mode(5);
|
||||||
|
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;
|
||||||
|
}
|
||||||
@@ -89,8 +89,8 @@ 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.210;
|
float zlim_lower = 0.1945;
|
||||||
float zlim_upper = 0.218;
|
float zlim_upper = 0.200;
|
||||||
|
|
||||||
//bool moved = false;
|
//bool moved = false;
|
||||||
//
|
//
|
||||||
@@ -121,8 +121,8 @@ public:
|
|||||||
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
|
//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
|
// 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));
|
//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));
|
||||||
@@ -233,13 +233,15 @@ 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 = "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_acceleration_scaling_factor = 0.98;
|
mpr.max_velocity_scaling_factor = 0.3;
|
||||||
|
mpr.max_acceleration_scaling_factor = 0.4;
|
||||||
|
//mpr.max_acceleration_scaling_factor = 0.1;
|
||||||
mpr.allowed_planning_time = 10;
|
mpr.allowed_planning_time = 10;
|
||||||
mpr.max_cartesian_speed = 2; // m/s
|
mpr.max_cartesian_speed = 3; // 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
|
||||||
|
|||||||
111
src/lite6_controller/src/lite6_trajectory_executor.cpp
Normal file
111
src/lite6_controller/src/lite6_trajectory_executor.cpp
Normal file
@@ -0,0 +1,111 @@
|
|||||||
|
#include <cstdio>
|
||||||
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
#include <robot_controller/robot_controller.hpp>
|
||||||
|
#include <chrono>
|
||||||
|
#include <cstdlib>
|
||||||
|
#include <queue>
|
||||||
|
|
||||||
|
#include <fstream>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include <geometry_msgs/msg/pose_stamped.hpp>
|
||||||
|
#include <geometry_msgs/msg/pose.hpp>
|
||||||
|
#include <moveit_msgs/msg/collision_object.hpp>
|
||||||
|
|
||||||
|
//#include <moveit/planning_interface/planning_interface.h>
|
||||||
|
//#include <moveit/planning_interface/planning_response.h>
|
||||||
|
//#include <moveit/kinematic_constraints/kinematic_constraint.h>
|
||||||
|
#include <moveit/kinematic_constraints/utils.h>
|
||||||
|
#include <moveit/move_group_interface/move_group_interface.h>
|
||||||
|
|
||||||
|
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||||
|
#include <tf2_eigen/tf2_eigen.hpp>
|
||||||
|
|
||||||
|
#include <moveit/planning_scene_interface/planning_scene_interface.h>
|
||||||
|
#include <moveit/move_group_interface/move_group_interface.h>
|
||||||
|
#include <moveit/common_planning_interface_objects/common_objects.h>
|
||||||
|
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
|
||||||
|
|
||||||
|
|
||||||
|
#include <moveit_msgs/msg/constraints.hpp>
|
||||||
|
#include <moveit_msgs/msg/robot_trajectory.hpp>
|
||||||
|
#include <moveit_msgs/msg/motion_plan_request.hpp>
|
||||||
|
#include <moveit_msgs/msg/motion_sequence_request.hpp>
|
||||||
|
#include <moveit_msgs/msg/motion_sequence_item.hpp>
|
||||||
|
#include <moveit_msgs/srv/get_motion_sequence.hpp>
|
||||||
|
|
||||||
|
|
||||||
|
#include <moveit/moveit_cpp/moveit_cpp.h>
|
||||||
|
#include <moveit/moveit_cpp/planning_component.h>
|
||||||
|
|
||||||
|
#include <moveit/robot_trajectory/robot_trajectory.h>
|
||||||
|
|
||||||
|
#include <pilz_industrial_motion_planner/command_list_manager.h>
|
||||||
|
|
||||||
|
const std::string MOVE_GROUP = "lite6";
|
||||||
|
|
||||||
|
using namespace std::chrono_literals;
|
||||||
|
|
||||||
|
class TrajectoryExecutor : public rclcpp::Node
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
//trajectory_pub = this->create_publisher<moveit_msgs::msg::RobotTrajectory>("lite6_trajectory", 10);
|
||||||
|
rclcpp::Subscription<moveit_msgs::msg::RobotTrajectory>::SharedPtr subscription;
|
||||||
|
moveit::planning_interface::MoveGroupInterface move_group;
|
||||||
|
|
||||||
|
rclcpp::TimerBase::SharedPtr trajectory_timer_;
|
||||||
|
std::queue<moveit_msgs::msg::RobotTrajectory> trajectory_queue;
|
||||||
|
bool busy = false;
|
||||||
|
|
||||||
|
TrajectoryExecutor(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
|
||||||
|
: Node("lite6_trajectory_executor",options),
|
||||||
|
move_group(std::shared_ptr<rclcpp::Node>(std::move(this)), MOVE_GROUP)
|
||||||
|
{
|
||||||
|
subscription = this->create_subscription<moveit_msgs::msg::RobotTrajectory>(
|
||||||
|
"lite6_trajectory", 100, std::bind(&TrajectoryExecutor::trajectory_callback, this, std::placeholders::_1));
|
||||||
|
|
||||||
|
trajectory_timer_ = this->create_wall_timer(
|
||||||
|
10ms, std::bind(&TrajectoryExecutor::executeTrajectoryFromQueue, this));
|
||||||
|
}
|
||||||
|
void trajectory_callback(const moveit_msgs::msg::RobotTrajectory msg)
|
||||||
|
{
|
||||||
|
RCLCPP_INFO(this->get_logger(), "Received trajectory, adding to queue");
|
||||||
|
//move_group.execute(msg);
|
||||||
|
trajectory_queue.push(msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void executeTrajectoryFromQueue()
|
||||||
|
{
|
||||||
|
if (busy || trajectory_queue.empty())
|
||||||
|
return;
|
||||||
|
busy = true;
|
||||||
|
RCLCPP_INFO(this->get_logger(), "Executing next trajectory from queue");
|
||||||
|
move_group.execute(trajectory_queue.front());
|
||||||
|
trajectory_queue.pop();
|
||||||
|
busy = false;
|
||||||
|
RCLCPP_INFO(this->get_logger(), "Finished executing trajectory");
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Starts lite6_controller
|
||||||
|
*/
|
||||||
|
int main(int argc, char ** argv)
|
||||||
|
{
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
|
||||||
|
auto trajectory_executor = std::make_shared<TrajectoryExecutor>();
|
||||||
|
|
||||||
|
// TODO remove sleep if not necessary
|
||||||
|
// Sleep in case move_group not loaded
|
||||||
|
rclcpp::sleep_for(2s);
|
||||||
|
|
||||||
|
//rclcpp::executors::SingleThreadedExecutor executor;
|
||||||
|
rclcpp::executors::MultiThreadedExecutor executor;
|
||||||
|
//executor.add_node(lite6);
|
||||||
|
executor.add_node(trajectory_executor);
|
||||||
|
executor.spin();
|
||||||
|
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return EXIT_SUCCESS;
|
||||||
|
}
|
||||||
@@ -40,6 +40,6 @@ endif()
|
|||||||
|
|
||||||
# Install directories
|
# Install directories
|
||||||
#install(DIRECTORY launch rviz urdf worlds DESTINATION share/${PROJECT_NAME})
|
#install(DIRECTORY launch rviz urdf worlds DESTINATION share/${PROJECT_NAME})
|
||||||
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
|
#install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
|
||||||
|
|
||||||
ament_package()
|
ament_package()
|
||||||
|
|||||||
@@ -73,7 +73,7 @@ class DrawingApp(tk.Tk):
|
|||||||
def draw(self,x,y,z):
|
def draw(self,x,y,z):
|
||||||
# putpixel is too slow
|
# putpixel is too slow
|
||||||
#self.img.putpixel((int(x), int(y)), (255, 0, 0))
|
#self.img.putpixel((int(x), int(y)), (255, 0, 0))
|
||||||
r = 4 # radius
|
r = 3 # radius
|
||||||
for xp in range(max(0, x-r), min(self.width-1, x+r)):
|
for xp in range(max(0, x-r), min(self.width-1, x+r)):
|
||||||
for yp in range(max(0, y-r), min(self.height-1, y+r)):
|
for yp in range(max(0, y-r), min(self.height-1, y+r)):
|
||||||
self.arr[xp,yp,0] = 0 #red
|
self.arr[xp,yp,0] = 0 #red
|
||||||
@@ -105,7 +105,7 @@ class DrawingApp(tk.Tk):
|
|||||||
#y = translate(p.y, -0.51, -0.3, 0, self.height)
|
#y = translate(p.y, -0.51, -0.3, 0, self.height)
|
||||||
|
|
||||||
x = int(translate(p.y, -0.5, 0.5, 0, self.width))
|
x = int(translate(p.y, -0.5, 0.5, 0, self.width))
|
||||||
y = int(translate(p.x, -0.3485, 0.1, 0, self.height))
|
y = int(translate(p.x, -0.2485, 0.1, 0, self.height))
|
||||||
|
|
||||||
#x = bound(self.width - x, 0, self.width)
|
#x = bound(self.width - x, 0, self.width)
|
||||||
#y = bound(self.height - y, 0, self.height)
|
#y = bound(self.height - y, 0, self.height)
|
||||||
|
|||||||
Reference in New Issue
Block a user