Skip to content

Commit 194ad27

Browse files
hilary-luoroni-kreinin
authored andcommitted
Initial Warthog addition
1 parent c869050 commit 194ad27

25 files changed

+951
-1
lines changed

clearpath_control/config/twist_mux.yaml

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,13 @@ twist_mux:
77
topics.interactive_marker.topic: twist_marker_server/cmd_vel
88
topics.interactive_marker.timeout: 0.5
99
topics.interactive_marker.priority: 8
10+
topics.rc.topic: rc_teleop/cmd_vel
11+
topics.rc.timeout: 0.5
12+
topics.rc.priority: 12
1013
topics.external.topic: cmd_vel
1114
topics.external.timeout: 0.5
1215
topics.external.priority: 1
1316
locks.e_stop.topic: platform/emergency_stop
1417
locks.e_stop.timeout: 0.0
15-
locks.e_stop.priority: 255
18+
locks.e_stop.priority: 255
19+
Lines changed: 69 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,69 @@
1+
controller_manager:
2+
ros__parameters:
3+
update_rate: 50 # Hz
4+
use_sim_time: False
5+
6+
joint_state_broadcaster:
7+
type: joint_state_broadcaster/JointStateBroadcaster
8+
9+
platform_velocity_controller:
10+
type: diff_drive_controller/DiffDriveController
11+
12+
platform_velocity_controller:
13+
ros__parameters:
14+
use_sim_time: False
15+
left_wheel_names: [ "front_left_wheel_joint", "rear_left_wheel_joint" ]
16+
right_wheel_names: [ "front_right_wheel_joint", "rear_right_wheel_joint" ]
17+
18+
wheel_separation: 1.08
19+
wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
20+
wheel_radius: 0.098 # TODO: Update this
21+
22+
wheel_separation_multiplier: 1.0
23+
left_wheel_radius_multiplier: 1.0
24+
right_wheel_radius_multiplier: 1.0
25+
26+
publish_rate: 50.0
27+
odom_frame_id: odom
28+
base_frame_id: base_link
29+
pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
30+
twist_covariance_diagonal: [0.001, 0.001, 0.001, 1000000.0, 1000000.0, 0.03]
31+
32+
open_loop: false
33+
enable_odom_tf: false
34+
35+
cmd_vel_timeout: 0.25
36+
#publish_limited_velocity: true
37+
use_stamped_vel: false
38+
#velocity_rolling_window_size: 10
39+
40+
# Preserve turning radius when limiting speed/acceleration/jerk
41+
preserve_turning_radius: true
42+
43+
# Publish limited velocity
44+
publish_cmd: true
45+
46+
# Publish wheel data
47+
publish_wheel_data: true
48+
49+
# Velocity and acceleration limits
50+
# Whenever a min_* is unspecified, default to -max_*
51+
linear.x.has_velocity_limits: true
52+
linear.x.has_acceleration_limits: true
53+
linear.x.has_jerk_limits: false
54+
linear.x.max_velocity: 5.0
55+
linear.x.min_velocity: -5.0
56+
linear.x.max_acceleration: 50.0
57+
linear.x.min_acceleration: -50.0
58+
linear.x.max_jerk: 0.0
59+
linear.x.min_jerk: 0.0
60+
61+
angular.z.has_velocity_limits: true
62+
angular.z.has_acceleration_limits: true
63+
angular.z.has_jerk_limits: false
64+
angular.z.max_velocity: 4.0
65+
angular.z.min_velocity: -4.0
66+
angular.z.max_acceleration: 40.0
67+
angular.z.min_acceleration: -40.0
68+
angular.z.max_jerk: 0.0
69+
angular.z.min_jerk: 0.0
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
ekf_node:
2+
ros__parameters:
3+
odom_frame: odom
4+
base_link_frame: base_link
5+
world_frame: odom
6+
publish_tf: true
7+
two_d_mode: true
8+
use_sim_time: false
9+
10+
frequency: 50.0
11+
12+
odom0: platform/odom
13+
odom0_config: [false, false, false,
14+
false, false, false,
15+
true, true, false,
16+
false, false, true,
17+
false, false, false]
18+
odom0_differential: false
19+
odom0_queue_size: 10
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
twist_server_node:
2+
ros__parameters:
3+
use_sim_time: False
4+
link_name: base_link
5+
robot: j100
6+
linear_scale: 1.0
7+
max_positive_linear_velocity: 1.0
8+
max_negative_linear_velocity: -1.0
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
# Teleop configuration for Logitech F710 Gamepad using the x-pad configuration.
2+
# Left thumb-stick up/down for velocity, left/right for twist
3+
# LB for enable
4+
# RB for enable-turbo
5+
#
6+
# (LB) (RB)
7+
# (LT) (RT)
8+
# _=====_ D( .)X _=====_
9+
# / _____ \ / _____ \
10+
# +.-'_____'-.---------------------------.-'_____'-.+
11+
# / | | '. .' | | \
12+
# / ___| /|\ |___ \ (back)(Lgtc)(strt) / ___| (Y) |___ \
13+
# / | | | ; __ __ ; | | |
14+
# | | <--- ---> | | (__) . (__) | | (X) (B)| |
15+
# | |___ | ___| ; MODE VIBE ; |___ ____| /
16+
# |\ | \|/ | / _ ___ _ \ | (A) | /|
17+
# | \ |_____| .','" "', |___| ,'" "', '. |_____| .' |
18+
# | '-.______.-' / \ANALOG/ \ '-._____.-' |
19+
# | | LJ |------| RJ | |
20+
# | /\ / \ /\ |
21+
# | / '.___.' '.___.' \ |
22+
# | / \ |
23+
# \ / \ /
24+
# \________/ \_________/
25+
#
26+
# BUTTON Value
27+
# LB 4
28+
# RB 5
29+
# A 0
30+
# B 1
31+
# X 2
32+
# Y 3
33+
#
34+
# AXIS Value
35+
# Left Horiz. 0
36+
# Left Vert. 1
37+
# Right Horiz. 3
38+
# Right Vert. 4
39+
# Left Trigger 2
40+
# Right Trigger 5
41+
# D-pad Horiz. 6
42+
# D-pad Vert. 7
43+
44+
joy_teleop/teleop_twist_joy_node:
45+
ros__parameters:
46+
use_sim_time: False
47+
axis_linear:
48+
x: 1
49+
scale_linear:
50+
x: 0.5
51+
scale_linear_turbo:
52+
x: 1.0
53+
axis_angular:
54+
yaw: 0
55+
scale_angular:
56+
yaw: 2.4
57+
scale_angular_turbo:
58+
yaw: 2.4
59+
enable_button: 4
60+
enable_turbo_button: 5
61+
joy_teleop/joy_node:
62+
ros__parameters:
63+
use_sim_time: False
64+
deadzone: 0.1
65+
autorepeat_rate: 20.0
66+
dev: /dev/input/f710
Lines changed: 79 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
# Teleop configuration for PS4 joystick using the x-pad configuration.
2+
# Left thumb-stick up/down for velocity, left/right for twist
3+
# Left shoulder button for enable
4+
# Right shoulder button for enable-turbo
5+
#
6+
# L1 R1
7+
# L2 R2
8+
# _=====_ _=====_
9+
# / _____ \ / _____ \
10+
# +.-'_____'-.------------------------------.-'_____'-.+
11+
# / | | '. S O N Y .' | _ | \
12+
# / ___| /|\ |___ \ / ___| /_\ |___ \ (Y)
13+
# / | | | ; ; | _ _ ||
14+
# | | <--- ---> | | | ||_| (_)|| (X) (B)
15+
# | |___ | ___| ; ; |___ ___||
16+
# |\ | \|/ | / _ ____ _ \ | (X) | /| (A)
17+
# | \ |_____| .','" "', (_PS_) ,'" "', '. |_____| .' |
18+
# | '-.______.-' / \ / \ '-._____.-' |
19+
# | | LJ |--------| RJ | |
20+
# | /\ / \ /\ |
21+
# | / '.___.' '.___.' \ |
22+
# | / \ |
23+
# \ / \ /
24+
# \________/ \_________/
25+
#
26+
# ^ x
27+
# |
28+
# |
29+
# y <-----+ Accelerometer axes
30+
# \
31+
# \
32+
# > z (out)
33+
#
34+
# BUTTON Value
35+
# L1 4
36+
# L2 6
37+
# R1 5
38+
# R2 7
39+
# A 1
40+
# B 2
41+
# X 0
42+
# Y 3
43+
#
44+
# AXIS Value
45+
# Left Horiz. 0
46+
# Left Vert. 1
47+
# Right Horiz. 2
48+
# Right Vert. 5
49+
# L2 3
50+
# R2 4
51+
# D-pad Horiz. 9
52+
# D-pad Vert. 10
53+
# Accel x 7
54+
# Accel y 6
55+
# Accel z 8
56+
57+
joy_teleop/teleop_twist_joy_node:
58+
ros__parameters:
59+
use_sim_time: False
60+
axis_linear:
61+
x: 1
62+
scale_linear:
63+
x: 0.5
64+
scale_linear_turbo:
65+
x: 1.0
66+
axis_angular:
67+
yaw: 0
68+
scale_angular:
69+
yaw: 2.4
70+
scale_angular_turbo:
71+
yaw: 2.4
72+
enable_button: 4
73+
enable_turbo_button: 5
74+
joy_teleop/joy_node:
75+
ros__parameters:
76+
use_sim_time: False
77+
deadzone: 0.1
78+
autorepeat_rate: 20.0
79+
dev: /dev/input/ps4
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.

0 commit comments

Comments
 (0)