Almost have joystick working

Added yaml config for ar3 simulation
Added moveit_servo to handle joystick inputs
Made launch file slightly more readable
Made joystickmove actually move the robot according to robot
Changed joystickmove executable name to move
This commit is contained in:
John Farrell 2021-09-20 20:25:09 -04:00
parent 21440062d4
commit 8527b2411e
Signed by: john
GPG key ID: 10543A0DA2EC1E12
4 changed files with 196 additions and 24 deletions

View file

@ -0,0 +1,69 @@
###############################################
# Modify all parameters related to servoing here
###############################################
use_gazebo: false # Whether the robot is started in a Gazebo simulation environment
## Properties of incoming commands
command_in_type: "unitless" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s
scale:
# Scale parameters are only used if command_in_type=="unitless"
linear: 0.4 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
rotational: 0.8 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands.
# Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic.
joint: 0.5
## Properties of outgoing commands
publish_period: 0.034 # 1/Nominal publish rate [seconds]
low_latency_mode: false # Set this to true to publish as soon as an incoming Twist command is received (publish_period is ignored)
# What type of topic does your robot driver expect?
# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory
command_out_type: trajectory_msgs/JointTrajectory
# What to publish? Can save some bandwidth as most robots only require positions or velocities
publish_joint_positions: true
publish_joint_velocities: false
publish_joint_accelerations: false
## Incoming Joint State properties
low_pass_filter_coeff: 2.0 # Larger --> trust the filtered data more, trust the measurements less.
## MoveIt properties
move_group_name: ar3_arm # Often 'manipulator' or 'arm'
planning_frame: base_link # The MoveIt planning frame. Often 'base_link' or 'world'
## Other frames
ee_frame_name: link_6 # The name of the end effector link, used to return the EE pose
robot_link_command_frame: base_link # commands must be given in the frame of a robot link. Usually either the base or end effector
## Stopping behaviour
incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command
# If 0, republish commands forever even if the robot is stationary. Otherwise, specify num. to publish.
# Important because ROS may drop some messages and we need the robot to halt reliably.
num_outgoing_halt_msgs_to_publish: 4
## Configure handling of singularities and joint limits
lower_singularity_threshold: 17.0 # Start decelerating when the condition number hits this (close to singularity)
hard_stop_singularity_threshold: 30.0 # Stop when the condition number hits this
joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger.
## Topic names
cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands
joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands
joint_topic: /joint_states
status_topic: ~/status # Publish status to this topic
command_out_topic: /joint_trajectory_controller/joint_trajectory # Publish outgoing commands here
## Collision checking for the entire robot body
check_collisions: true # Check collisions?
collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
# Two collision check algorithms are available:
# "threshold_distance" begins slowing down when nearer than a specified distance. Good if you want to tune collision thresholds manually.
# "stop_distance" stops if a collision is nearer than the worst-case stopping distance and the distance is decreasing. Requires joint acceleration limits
collision_check_type: threshold_distance
# Parameters for "threshold_distance"-type collision checking
self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m]
scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m]
# Parameters for "stop_distance"-type collision checking
collision_distance_safety_factor: 1000.0 # Must be >= 1. A large safety factor is recommended to account for latency
min_allowable_collision_distance: 0.01 # Stop if a collision is closer than this [m]

View file

@ -1,7 +1,8 @@
from os.path import join
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
from launch_ros.actions import Node, ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.actions import ExecuteProcess
import yaml
@ -30,36 +31,68 @@ def generate_launch_description():
executable='rviz2',
output='log',
arguments=['-d', join(launch_root, 'rviz', 'ar3.rviz')],
parameters=[robot_description, robot_description_semantic, robot_description_kinematics]),
parameters=[robot_description, robot_description_semantic, robot_description_kinematics],
),
# Attatch robot to map
Node(
package='tf2_ros',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'world', 'base_link']),
arguments=['0', '0', '0', '0', '0', '0', 'world', 'base_link'],
),
Node(
package='joystickmove',
executable='move',
output='screen',
),
# Create joystick controller
ComposableNodeContainer(
name="joystick_container",
namespace="/",
package="rclcpp_components",
executable="component_container",
composable_node_descriptions=[
ComposableNode(
package="moveit_servo",
plugin="moveit_servo::ServoServer",
name="servo_server",
parameters=[
{'moveit_servo': get_yaml(join(config_root, 'ar3_joy.yaml'))},
robot_description,
robot_description_semantic,
],
extra_arguments=[{"use_intra_process_comms": True}],
),
ComposableNode(
package="joy",
plugin="joy::Joy",
name="joy_node",
extra_arguments=[{"use_intra_process_comms": True}],
)
],
output="screen",
),
# Controller
Node(
package='controller_manager',
executable='ros2_control_node',
output='screen',
parameters=[robot_description, join(config_root, 'controller_manager.yaml')]),
parameters=[robot_description, join(config_root, 'controller_manager.yaml')],
),
# Start controllers
ExecuteProcess(
cmd=['ros2 run controller_manager spawner.py joint_trajectory_controller'],
shell=True,
output='screen'),
output='screen',
),
ExecuteProcess(
cmd=['ros2 run controller_manager spawner.py joint_state_controller'],
shell=True,
output='screen'),
# Run platform
Node(
package='cobot_platform',
executable='move',
output='screen',
),
@ -74,7 +107,7 @@ def generate_launch_description():
robot_description_kinematics,
{'move_group': join(config_root, 'ompl_planning.yaml')},
{'moveit_simple_controller_manager': join(config_root, "ar3_controllers.yaml")},
],
]
),
# Robot state publisher
@ -82,13 +115,14 @@ def generate_launch_description():
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[robot_description]),
parameters=[robot_description],
),
# Fake robot state publisher
# Node(
# package='ar3_description',
# executable='state_publisher',
# name='state_publisher',
# emulate_tty=True,
# output='screen'),
# Interface with arduino
Node(
package='cobot_platform',
executable='move',
output='screen',
),
])

View file

@ -1,8 +1,39 @@
import rclpy
from rclpy.node import Node
from std_srvs.srv import Trigger
from std_msgs.msg import Float32
from sensor_msgs.msg import Joy
from geometry_msgs.msg import TwistStamped
from moveit_msgs.msg import PlanningScene
from enum import Enum
class Buttons(Enum):
CROSS = 0
CIRCLE = 1
TRIANGLE = 2
SQUARE = 3
L1 = 4
R1 = 5
L2 = 6
R2 = 7
SELECT = 8
START = 9
CENTER = 10
L3 = 11
R3 = 12
class Axes(Enum):
LEFT_X = 0
LEFT_Y = 1
L1 = 2
RIGHT_X = 3
RIGHT_Y = 4
R1 = 5
DPAD_UPDOWN = 6
DPAD_LEFTRIGHT = 7
class JoyMove(Node):
def __init__(self):
@ -10,13 +41,51 @@ class JoyMove(Node):
self._logger = self.get_logger()
self._logger.info('joystick init')
JOY_TOPIC = '/joy'
TWIST_TOPIC = '/servo_server/delta_twist_cmds'
# JOINT_TOPIC = '/servo_server/delta_joint_cmds'
# EE = 'joint_6'
# BASE = 'base_link'
self.create_subscription(Joy, '/joy', self._joy_cb, rclpy.qos.qos_profile_sensor_data)
self.base_pub = self.create_publisher(Float32, '/move/j1', 10)
self.base_pub = self.create_publisher(Float32, JOY_TOPIC, 10)
self.twist_pub = self.create_publisher(TwistStamped, TWIST_TOPIC, 10);
# self.collision_pub = self.create_publisher(PlanningScene, "/planning_scene", 10);
self.servo_client = self.create_client(Trigger, '/servo_server/start_servo')
# Check if the a service is available
while not self.servo_client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('servo_server not available, waiting again...')
self._logger.info('servo_server connected.')
req = Trigger.Request()
self.servo_client.call_async(req)
def _joy_cb(self, msg):
asd = msg.axes[1]
self.base_pub.publish(Float32(data=asd))
axes = msg.axes
buttons = msg.buttons
ts = TwistStamped()
ts.twist.linear.z = axes[Axes.RIGHT_Y.value]
ts.twist.linear.y = axes[Axes.RIGHT_X.value]
lin_x_right = -0.5 * axes[Axes.R1.value] # - AXIS_DEFAULTS.at(R1));
lin_x_left = 0.5 * axes[Axes.L1.value] # - AXIS_DEFAULTS.at(L1));
ts.twist.linear.x = lin_x_right + lin_x_left
ts.twist.angular.y = axes[Axes.LEFT_Y.value]
ts.twist.angular.x = axes[Axes.LEFT_X.value]
roll_positive = buttons[Buttons.R2.value]
roll_negative = -1 * buttons[Buttons.L2.value]
ts.twist.angular.z = float(roll_positive + roll_negative)
ts.header.stamp = self.get_clock().now().to_msg()
self.twist_pub.publish(ts)
def main(args=None):

View file

@ -20,7 +20,7 @@ setup(
tests_require=['pytest'],
entry_points={
'console_scripts': [
'joystickmove = joystickmove.move:main'
'move = joystickmove.move:main'
],
},
)