Skip to content

Commit 68dbf2e

Browse files
committed
ackerman steering done
1 parent 8dee9f8 commit 68dbf2e

File tree

4 files changed

+110
-117
lines changed

4 files changed

+110
-117
lines changed

mars_rover/config/mars_rover_control.yaml

Lines changed: 29 additions & 43 deletions
Original file line numberDiff line numberDiff line change
@@ -9,45 +9,45 @@ controller_manager:
99
type: joint_trajectory_controller/JointTrajectoryController
1010

1111
wheel_velocity_controller:
12-
type: joint_trajectory_controller/JointTrajectoryController
12+
type: velocity_controllers/JointGroupVelocityController
1313

1414
steer_position_controller:
15-
type: joint_trajectory_controller/JointTrajectoryController
15+
type: position_controllers/JointGroupPositionController
1616

1717
wheel_tree_position_controller:
18-
type: joint_trajectory_controller/JointTrajectoryController
18+
type: position_controllers/JointGroupPositionController
1919

2020
joint_state_broadcaster:
2121
type: joint_state_broadcaster/JointStateBroadcaster
2222

2323

24-
arm_joint_trajectory_controller:
25-
ros__parameters:
26-
joints:
27-
- arm_01_joint
28-
- arm_02_joint
29-
- arm_03_joint
30-
- arm_04_joint
31-
- arm_tools_joint
32-
interface_name: position
33-
command_interfaces:
34-
- position
35-
state_interfaces:
36-
- position
37-
- velocity
24+
# arm_joint_trajectory_controller:
25+
# ros__parameters:
26+
# joints:
27+
# - arm_01_joint
28+
# - arm_02_joint
29+
# - arm_03_joint
30+
# - arm_04_joint
31+
# - arm_tools_joint
32+
# interface_name: position
33+
# command_interfaces:
34+
# - position
35+
# state_interfaces:
36+
# - position
37+
# - velocity
3838

39-
mast_joint_trajectory_controller:
40-
ros__parameters:
41-
joints:
42-
- mast_p_joint
43-
- mast_02_joint
44-
- mast_cameras_joint
45-
interface_name: position
46-
command_interfaces:
47-
- position
48-
state_interfaces:
49-
- position
50-
- velocity
39+
# mast_joint_trajectory_controller:
40+
# ros__parameters:
41+
# joints:
42+
# - mast_p_joint
43+
# - mast_02_joint
44+
# - mast_cameras_joint
45+
# interface_name: position
46+
# command_interfaces:
47+
# - position
48+
# state_interfaces:
49+
# - position
50+
# - velocity
5151

5252
wheel_velocity_controller:
5353
ros__parameters:
@@ -59,11 +59,6 @@ wheel_velocity_controller:
5959
- middle_wheel_R_joint
6060
- back_wheel_R_joint
6161
interface_name: velocity
62-
command_interfaces:
63-
- velocity
64-
state_interfaces:
65-
- position
66-
- velocity
6762

6863

6964
steer_position_controller:
@@ -74,11 +69,6 @@ steer_position_controller:
7469
- suspension_steer_F_R_joint
7570
- suspension_steer_B_R_joint
7671
interface_name: position
77-
command_interfaces:
78-
- position
79-
state_interfaces:
80-
- position
81-
- velocity
8272

8373
wheel_tree_position_controller:
8474
ros__parameters:
@@ -90,7 +80,3 @@ wheel_tree_position_controller:
9080
- suspension_arm_B_R_joint
9181
- suspension_arm_B2_R_joint
9282
interface_name: position
93-
command_interfaces:
94-
- position
95-
state_interfaces:
96-
- position

mars_rover/launch/mars_rover.launch.py

Lines changed: 11 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ def generate_launch_description():
7373
arguments=[
7474
'-name', 'curiosity_mars_rover',
7575
'-x','1.0',
76-
'-z','-7.0',
76+
'-z','-7.4',
7777
'-y','0.0',
7878
'-topic', '/robot_description'
7979
],
@@ -99,17 +99,17 @@ def generate_launch_description():
9999
output='screen'
100100
)
101101

102-
load_arm_joint_traj_controller = ExecuteProcess(
103-
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
104-
'arm_joint_trajectory_controller'],
105-
output='screen'
106-
)
102+
# load_arm_joint_traj_controller = ExecuteProcess(
103+
# cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
104+
# 'arm_joint_trajectory_controller'],
105+
# output='screen'
106+
# )
107107

108-
load_mast_joint_traj_controller = ExecuteProcess(
109-
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
110-
'mast_joint_trajectory_controller'],
111-
output='screen'
112-
)
108+
# load_mast_joint_traj_controller = ExecuteProcess(
109+
# cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
110+
# 'mast_joint_trajectory_controller'],
111+
# output='screen'
112+
# )
113113

114114
load_wheel_joint_traj_controller = ExecuteProcess(
115115
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
@@ -157,8 +157,6 @@ def generate_launch_description():
157157
OnProcessExit(
158158
target_action=set_hardware_interface_active,
159159
on_exit=[load_joint_state_broadcaster,
160-
load_arm_joint_traj_controller,
161-
load_mast_joint_traj_controller,
162160
load_wheel_joint_traj_controller,
163161
load_steer_joint_traj_controller,
164162
load_suspension_joint_traj_controller],

mars_rover/nodes/move_wheel

Lines changed: 65 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -4,69 +4,89 @@ import rclpy
44
from rclpy.node import Node
55
from builtin_interfaces.msg import Duration
66

7-
from std_msgs.msg import String, Float64
7+
from std_msgs.msg import String, Float64MultiArray
88
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
9+
from geometry_msgs.msg import Twist
10+
import math
911

1012
class MoveWheel(Node):
1113

1214
def __init__(self):
1315
super().__init__('wheel_node')
14-
self.wheel_publisher_ = self.create_publisher(JointTrajectory, '/wheel_velocity_controller/joint_trajectory', 10)
15-
self.steer_publisher_ = self.create_publisher(JointTrajectory, '/steer_position_controller/joint_trajectory', 10)
16-
# self.suspension_publisher_ = self.create_publisher(JointTrajectory, '/wheel_tree_position_controller/joint_trajectory',10)
17-
timer_period = 0.5 # seconds
16+
self.wheel_publisher_ = self.create_publisher(Float64MultiArray, '/wheel_velocity_controller/commands', 10)
17+
self.steer_publisher_ = self.create_publisher(Float64MultiArray, '/steer_position_controller/commands', 10)
18+
self.suspension_publisher_ = self.create_publisher(Float64MultiArray, '/wheel_tree_position_controller/commands',10)
19+
timer_period = 0.1 # seconds
1820
self.timer = self.create_timer(timer_period, self.timer_callback)
1921

2022

21-
def timer_callback(self):
22-
#wheel velocities
23-
traj = JointTrajectory()
24-
traj.joint_names = ["front_wheel_L_joint",
25-
"middle_wheel_L_joint",
26-
"back_wheel_L_joint",
27-
"front_wheel_R_joint",
28-
"middle_wheel_R_joint",
29-
"back_wheel_R_joint"]
30-
31-
point = JointTrajectoryPoint()
32-
point.positions = [0.0,0.0,0.0,0.0,0.0,0.0]
33-
point.time_from_start = Duration(sec=1)
23+
self.vel_sub = self.create_subscription(Twist, '/cmd_vel', self.vel_callback, 10)
24+
self.curr_vel = Twist()
3425

35-
traj.points.append(point)
36-
self.wheel_publisher_.publish(traj)
26+
def vel_callback(self, msg):
27+
self.curr_vel = msg
3728

29+
def set_wheel_common_speed(self, vel):
3830

39-
#steering wheel
40-
steer_traj = JointTrajectory()
41-
steer_traj.joint_names = ["suspension_steer_F_L_joint",
42-
"suspension_steer_B_L_joint",
43-
"suspension_steer_F_R_joint",
44-
"suspension_steer_B_R_joint"]
31+
target_vel = Float64MultiArray()
32+
target_vel.data = [vel for i in range(3)] + [-vel for i in range(3,6)]
4533

46-
steer_point = JointTrajectoryPoint()
47-
steer_point.positions = [1.0,1.0,0.0,0.0]
48-
steer_point.time_from_start = Duration(sec=1)
34+
# self.get_logger().info(f'Publishing: "{target_vel.data}"')
35+
self.wheel_publisher_.publish(target_vel)
4936

50-
steer_traj.points.append(steer_point)
51-
self.steer_publisher_.publish(steer_traj)
5237

53-
# #wheel suspension
54-
# suspension_traj = JointTrajectory()
55-
# suspension_traj.joint_names = ["suspension_arm_F_L_joint",
56-
# "suspension_arm_B_L_joint",
57-
# "suspension_arm_B2_L_joint",
58-
# "suspension_arm_F_R_joint",
59-
# "suspension_arm_B_R_joint",
60-
# "suspension_arm_B2_R_joint"]
38+
def map_angular_to_steering(self, angular_speed) -> float:
39+
if abs(angular_speed) < 1e-3:
40+
return 0.0
6141

62-
# suspension_point = JointTrajectoryPoint()
63-
# suspension_point.positions = [0.0,0.0,0.0,0.0,0.0,0.0]
64-
# suspension_point.time_from_start = Duration(sec=1)
42+
#max 0.6 min -0.6
43+
angular_speed = min(0.6, max(angular_speed, -0.6))
44+
return (angular_speed/abs(angular_speed))*(-25 * abs(angular_speed) + 17.5)
6545

66-
# suspension_traj.points.append(suspension_point)
67-
# self.suspension_publisher_.publish(suspension_traj)
6846

69-
47+
def set_steering(self, turn_rad):
48+
target_steer = Float64MultiArray()
49+
if abs(turn_rad) < 1e-3:
50+
target_steer.data = [0.0, 0.0, 0.0, 0.0]
51+
else:
52+
R = abs(turn_rad) #Turning radius
53+
54+
L = 2.08157 #Chassis Length
55+
T = 1.53774 #Chassis Width
56+
57+
alpha_i = math.atan(L/(R - (T/2)))
58+
alpha_o = math.atan(L/(R + (T/2)))
59+
60+
if alpha_i > 0.6:
61+
alpha_i = 0.6
62+
63+
if alpha_o > 0.6:
64+
alpha_o = 0.6
65+
66+
if turn_rad > 0.0:
67+
target_steer.data = [alpha_i, -alpha_i, alpha_o, -alpha_o]
68+
else:
69+
target_steer.data = [-alpha_o, alpha_o, -alpha_i, alpha_i]
70+
71+
self.get_logger().info(f'Publishing: "{target_steer.data}"')
72+
self.steer_publisher_.publish(target_steer)
73+
74+
75+
def set_suspension(self, sus_val=None):
76+
77+
target_val = Float64MultiArray()
78+
if sus_val is None:
79+
target_val.data = [0.1,0.0,-0.1,0.1,0.0,-0.1]
80+
self.suspension_publisher_.publish(target_val)
81+
82+
83+
def timer_callback(self):
84+
self.set_wheel_common_speed(self.curr_vel.linear.x)
85+
self.set_suspension()
86+
87+
steering_val = self.map_angular_to_steering(self.curr_vel.angular.z)
88+
self.set_steering(steering_val)
89+
7090

7191
def main(args=None):
7292
rclpy.init(args=args)

mars_rover/urdf/curiosity_mars_rover.xacro

Lines changed: 5 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
<hardware>
3131
<plugin>ign_ros2_control/IgnitionSystem</plugin>
3232
</hardware>
33+
<!-- Arm Joints Interfaces-->
3334
<joint name="arm_01_joint">
3435
<command_interface name="position" />
3536
<state_interface name="position" />
@@ -56,6 +57,7 @@
5657
<state_interface name="position" />
5758
<state_interface name="velocity" />
5859
</joint>
60+
<!-- Mast Joints Interfaces-->
5961
<joint name="mast_p_joint">
6062
<command_interface name="position" />
6163
<state_interface name="position" />
@@ -71,56 +73,43 @@
7173
<state_interface name="position" />
7274
<state_interface name="velocity" />
7375
</joint>
76+
<!-- Wheel Joints Interfaces-->
7477
<joint name="front_wheel_L_joint">
7578
<command_interface name="velocity" />
76-
<state_interface name="position" />
77-
<state_interface name="velocity" />
7879
</joint>
7980
<joint name="middle_wheel_L_joint">
8081
<command_interface name="velocity" />
81-
<state_interface name="position" />
82-
<state_interface name="velocity" />
8382
</joint>
8483
<joint name="back_wheel_L_joint">
8584
<command_interface name="velocity" />
86-
<state_interface name="position" />
87-
<state_interface name="velocity" />
8885
</joint>
8986
<joint name="front_wheel_R_joint">
9087
<command_interface name="velocity" />
91-
<state_interface name="position" />
92-
<state_interface name="velocity" />
9388
</joint>
9489
<joint name="middle_wheel_R_joint">
9590
<command_interface name="velocity" />
96-
<state_interface name="position" />
97-
<state_interface name="velocity" />
9891
</joint>
9992
<joint name="back_wheel_R_joint">
10093
<command_interface name="velocity" />
101-
<state_interface name="position" />
102-
<state_interface name="velocity" />
10394
</joint>
95+
<!-- Steering Joints Interfaces-->
10496
<joint name="suspension_steer_F_L_joint">
10597
<command_interface name="position" />
10698
<state_interface name="position" />
107-
<state_interface name="velocity" />
10899
</joint>
109100
<joint name="suspension_steer_B_L_joint">
110101
<command_interface name="position" />
111102
<state_interface name="position" />
112-
<state_interface name="velocity" />
113103
</joint>
114104
<joint name="suspension_steer_F_R_joint">
115105
<command_interface name="position" />
116106
<state_interface name="position" />
117-
<state_interface name="velocity" />
118107
</joint>
119108
<joint name="suspension_steer_B_R_joint">
120109
<command_interface name="position" />
121110
<state_interface name="position" />
122-
<state_interface name="velocity" />
123111
</joint>
112+
<!-- Suspension Arms Interfaces-->
124113
<joint name="suspension_arm_F_L_joint">
125114
<command_interface name="position" />
126115
<state_interface name="position" />

0 commit comments

Comments
 (0)