Skip to content

Commit f0a9d24

Browse files
committed
new sentry xacro file modified
1 parent 019fdd4 commit f0a9d24

9 files changed

Lines changed: 85 additions & 31 deletions

File tree

decomposition/meta_chassis_controller/src/agv_chassis_controller.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ using ControllerReferenceMsg =
2121
namespace meta_chassis_controller {
2222
using hardware_interface::HW_IF_POSITION;
2323
using hardware_interface::HW_IF_VELOCITY;
24+
using hardware_interface::HW_IF_EFFORT;
2425

2526
void reset_controller_reference_msg(
2627
const std::shared_ptr<ControllerReferenceMsg> &msg,
@@ -140,7 +141,7 @@ AgvChassisController::command_interface_configuration() const {
140141
command_interfaces_config.names.push_back(joint + "/" + HW_IF_VELOCITY);
141142
}
142143
for (const auto &joint : params_.agv_pos_joints) {
143-
command_interfaces_config.names.push_back(joint + "/" + HW_IF_POSITION);
144+
command_interfaces_config.names.push_back(joint + "/" + HW_IF_EFFORT);
144145
}
145146

146147
return command_interfaces_config;
@@ -268,6 +269,7 @@ AgvChassisController::update_and_write_commands(const rclcpp::Time &time,
268269
}
269270

270271
agv_wheel_kinematics_->inverse(twist, wheels_pos_, wheels_vel_);
272+
271273
for (size_t i = 0; i < 4; i++) {
272274
command_interfaces_[i].set_value(wheels_vel_[static_cast<Eigen::Index>(i)]);
273275
command_interfaces_[i + 4].set_value(wheels_pos_[static_cast<Eigen::Index>(i)]);

decomposition/metav_description/urdf/common/steer_wheel.xacro

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222
<inertia ixx="1.416e-3" ixy="0.0" ixz="0.0" iyy="2.749e-3" iyz="0.0" izz="1.416e-3" />
2323
</inertial>
2424
</link>
25-
<!-- TODO: Params unchanged -->
2625
<link name="${prefix}_wheel">
2726
<visual>
2827
<geometry>

decomposition/metav_description/urdf/sentry25/sentry.chassis.xacro

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<?xml version="1.0"?>
2-
<robot name="sentry" xmlns:xacro="http://www.ros.org/wiki/xacro">
3-
<xacro:include filename="$(find metav_description)/urdf/common/omni_wheel.xacro"/>
2+
<robot name="sentry25" xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
<xacro:include filename="$(find metav_description)/urdf/common/steer_wheel.xacro"/>
44

55
<xacro:property name="chassis_radius" value="0.245"/>
66
<xacro:property name="wheel_offset_z" value="0.0"/>

decomposition/metav_description/urdf/sentry25/sentry.gazebo.xacro

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<?xml version="1.0"?>
2-
<robot name="sentry" xmlns:xacro="http://www.ros.org/wiki/xacro">
2+
<robot name="sentry25" xmlns:xacro="http://www.ros.org/wiki/xacro">
33

44
<gazebo>
55
<plugin filename="ign_ros2_control-system"

decomposition/metav_description/urdf/sentry25/sentry.gimbal.xacro

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<?xml version="1.0"?>
2-
<robot name="sentry" xmlns:xacro="http://www.ros.org/wiki/xacro">
2+
<robot name="sentry25" xmlns:xacro="http://www.ros.org/wiki/xacro">
33

44
<xacro:property name="threshold" value="0.08" />
55
<xacro:property name="pitch_lower_limit" value="-0.72" />

decomposition/metav_description/urdf/sentry25/sentry.shooter.xacro

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<?xml version="1.0"?>
2-
<robot name="sentry" xmlns:xacro="http://www.ros.org/wiki/xacro">
2+
<robot name="sentry25" xmlns:xacro="http://www.ros.org/wiki/xacro">
33

44
<xacro:macro name="shooter" params="">
55

decomposition/metav_description/urdf/sentry25/sentry.xacro

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<?xml version="1.0"?>
2-
<robot name="sentry" xmlns:xacro="http://www.ros.org/wiki/xacro">
2+
<robot name="sentry25" xmlns:xacro="http://www.ros.org/wiki/xacro">
33

44
<xacro:arg name="is_simulation" default="true" />
55

@@ -13,18 +13,18 @@
1313
<child link="base_link" />
1414
</joint>
1515

16-
<xacro:include filename="$(find metav_description)/urdf/sentry/sentry.chassis.xacro" />
16+
<xacro:include filename="$(find metav_description)/urdf/sentry25/sentry.chassis.xacro" />
1717
<xacro:if value="$(arg is_simulation)">
1818
<xacro:chassis roller_type="simple" />
1919
</xacro:if>
2020
<xacro:unless value="$(arg is_simulation)">
2121
<xacro:chassis roller_type="none" />
2222
</xacro:unless>
2323

24-
<xacro:include filename="$(find metav_description)/urdf/sentry/sentry.gimbal.xacro" />
24+
<xacro:include filename="$(find metav_description)/urdf/sentry25/sentry.gimbal.xacro" />
2525
<xacro:gimbal />
2626

27-
<xacro:include filename="$(find metav_description)/urdf/sentry/sentry.shooter.xacro" />
27+
<xacro:include filename="$(find metav_description)/urdf/sentry25/sentry.shooter.xacro" />
2828
<xacro:shooter />
2929

3030
<xacro:include filename="$(find metav_description)/urdf/common/sensor_imu.xacro" />

meta_bringup/config/sentry25.yaml

Lines changed: 68 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -2,12 +2,18 @@ controller_manager:
22
ros__parameters:
33
update_rate: 200 # Hz
44

5-
omni_chassis_controller:
6-
type: meta_chassis_controller/OmniChassisController
5+
agv_chassis_controller:
6+
type: meta_chassis_controller/AgvChassisController
77

88
wheels_pid_controller:
99
type: pid_controller/PidController
1010

11+
steer_pos2vel_pid_controller:
12+
type: pid_controller/PidController
13+
14+
steer_vel2eff_pid_controller:
15+
type: pid_controller/PidController
16+
1117
gimbal_controller:
1218
type: meta_gimbal_controller/GimbalController
1319

@@ -25,10 +31,14 @@ agv_chassis_controller:
2531
- wheels_pid_controller/right_forward_vel_joint
2632
- wheels_pid_controller/right_back_vel_joint
2733
agv_pos_joints:
28-
- wheels_pid_controller/left_forward_pos_joint
29-
- wheels_pid_controller/left_back_pos_joint
30-
- wheels_pid_controller/right_forward_pos_joint
31-
- wheels_pid_controller/right_back_pos_joint
34+
# - steer_pos2vel_pid_controller/left_forward_pos_joint
35+
# - steer_pos2vel_pid_controller/left_back_pos_joint
36+
# - steer_pos2vel_pid_controller/right_forward_pos_joint
37+
# - steer_pos2vel_pid_controller/right_back_pos_joint
38+
- left_forward_pos_joint
39+
- left_back_pos_joint
40+
- right_forward_pos_joint
41+
- right_back_pos_joint
3242

3343
agv_wheel_center_x: 0.225
3444
agv_wheel_center_y: 0.225
@@ -44,6 +54,12 @@ agv_chassis_controller:
4454

4555
follow_pid_target: 0.7853981634
4656

57+
steer_pos_pos2vel_gains:
58+
{ p: 4.0, i: 2.0e-1, d: 0.0, i_clamp_max: 3.0, i_clamp_min: -3.0, antiwindup: true }
59+
steer_pos_vel2eff_gains:
60+
{ p: 4.0, i: 2.0e-1, d: 0.0, i_clamp_max: 3.0, i_clamp_min: -3.0, antiwindup: true }
61+
62+
4763
reference_timeout: 0.2
4864

4965
wheels_pid_controller:
@@ -53,10 +69,6 @@ wheels_pid_controller:
5369
- left_back_vel_joint
5470
- right_forward_vel_joint
5571
- right_back_vel_joint
56-
- left_forward_pos_joint
57-
- left_back_pos_joint
58-
- right_forward_pos_joint
59-
- right_back_pos_joint
6072

6173
command_interface: effort
6274

@@ -71,14 +83,52 @@ wheels_pid_controller:
7183
{ p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
7284
right_back_vel_joint:
7385
{ p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
74-
left_forward_pos_joint:
75-
{ p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
76-
left_back_pos_joint:
77-
{ p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
78-
right_forward_pos_joint:
79-
{ p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
80-
right_back_pos_joint:
81-
{ p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
86+
87+
88+
# steer_vel2eff_pid_controller:
89+
# ros__parameters:
90+
# dof_names:
91+
# - left_forward_pos_joint
92+
# - left_back_pos_joint
93+
# - right_forward_pos_joint
94+
# - right_back_pos_joint
95+
96+
# command_interface: effort
97+
98+
# reference_and_state_interfaces: ["vel_cmd"]
99+
100+
# gains:
101+
# left_forward_pos_joint:
102+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
103+
# left_back_pos_joint:
104+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
105+
# right_forward_pos_joint:
106+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
107+
# right_back_pos_joint:
108+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
109+
110+
# steer_pos2vel_pid_controller:
111+
# ros__parameters:
112+
# dof_names:
113+
# - left_forward_pos_joint
114+
# - left_back_pos_joint
115+
# - right_forward_pos_joint
116+
# - right_back_pos_joint
117+
118+
# command_interface: effort
119+
120+
# reference_and_state_interfaces: ["position"]
121+
122+
# gains:
123+
# left_forward_pos_joint:
124+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
125+
# left_back_pos_joint:
126+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
127+
# right_forward_pos_joint:
128+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true }
129+
# right_back_pos_joint:
130+
# { p: 2.0e-2, i: 1.0e-4, d: 0.0, i_clamp_max: 1.0, i_clamp_min: -1.0, antiwindup: true } # TODO: PID parameters to finish
131+
82132

83133
gimbal_controller:
84134
ros__parameters:

meta_bringup/launch/sentry25.launch.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ def generate_launch_description():
3535
PathJoinSubstitution([FindExecutable(name='xacro')]),
3636
' ',
3737
PathJoinSubstitution(
38-
[FindPackageShare('metav_description'), 'urdf', 'sentry', 'sentry.xacro']),
38+
[FindPackageShare('metav_description'), 'urdf', 'sentry25', 'sentry.xacro']),
3939
' ',
4040
'is_simulation:=', enable_simulation,
4141
])
@@ -92,7 +92,10 @@ def generate_launch_description():
9292
# List of controllers to be loaded sequentially
9393
# Order in this list is IMPORTANT
9494
load_controllers = [
95-
# load_controller('wheels_pid_controller'),
95+
load_controller('wheels_pid_controller'),
96+
load_controller('steer_pos2vel_pid_controller'),
97+
# load_controller('steer_vel2eff_pid_controller'),
98+
9699
# load_controller('gimbal_controller'),
97100
load_controller('agv_chassis_controller'),
98101
# load_controller('shoot_controller')

0 commit comments

Comments
 (0)