Skip to content

Commit 019fdd4

Browse files
committed
Merge branch 'master' into wfy
2 parents 8653eed + cc7af97 commit 019fdd4

File tree

10 files changed

+699
-16
lines changed

10 files changed

+699
-16
lines changed
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
<?xml version="1.0"?>
2+
<robot name="standard_omni" xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
<xacro:include filename="$(find metav_description)/urdf/common/omni_wheel.xacro"/>
4+
5+
<xacro:property name="chassis_radius" value="0.245"/>
6+
<xacro:property name="wheel_offset_z" value="0.0"/>
7+
8+
<xacro:macro name="chassis" params="roller_type">
9+
10+
<link name="base_link">
11+
<inertial>
12+
<mass value="12.326"/>
13+
<origin xyz="-0.000932 -0.000668 -0.01"/>
14+
<inertia ixx="1.924e-1" ixy="-6.458e-4" ixz="5.951352e-3" iyy="2.473e-1"
15+
iyz="-7.22e-4" izz="3.187e-1"/>
16+
</inertial>
17+
<visual>
18+
<origin xyz="0 0 0" rpy="0 0 0"/>
19+
<geometry>
20+
<mesh filename="file://$(find metav_description)/meshes/sentry/chassis.stl" scale="1.0 1.0 1.0"/>
21+
</geometry>
22+
<material name="silver">
23+
<color rgba="0.700 0.700 0.700 1.000"/>
24+
</material>
25+
</visual>
26+
<collision>
27+
<origin xyz="0 0 0" rpy="0 0 0"/>
28+
<geometry>
29+
<box size="0.392 0.392 0.14"/>
30+
</geometry>
31+
</collision>
32+
</link>
33+
34+
<xacro:omni_wheel prefix="front" connected_to="base_link"
35+
wheel_x_offset="${chassis_radius}" wheel_y_offset="0.0"
36+
wheel_z_offset="${wheel_offset_z}" rotation_degree="${-pi/2}" roller_type="${roller_type}"
37+
max_effort="3.42" max_velocity="73"
38+
/>
39+
<xacro:omni_wheel prefix="right" connected_to="base_link"
40+
wheel_x_offset="0.0" wheel_y_offset="${-chassis_radius}"
41+
wheel_z_offset="${wheel_offset_z}" rotation_degree="${pi}" roller_type="${roller_type}"
42+
max_effort="3.42" max_velocity="73"
43+
/>
44+
<xacro:omni_wheel prefix="left" connected_to="base_link"
45+
wheel_x_offset="0.0" wheel_y_offset="${chassis_radius}"
46+
wheel_z_offset="${wheel_offset_z}" rotation_degree="${0}" roller_type="${roller_type}"
47+
max_effort="3.42" max_velocity="73"
48+
/>
49+
<xacro:omni_wheel prefix="back" connected_to="base_link"
50+
wheel_x_offset="${-chassis_radius}" wheel_y_offset="${0}"
51+
wheel_z_offset="${wheel_offset_z}" rotation_degree="${pi/2}" roller_type="${roller_type}"
52+
max_effort="3.42" max_velocity="73"
53+
/>
54+
55+
</xacro:macro>
56+
57+
</robot>
Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
<?xml version="1.0"?>
2+
<robot name="standard_omni" xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
4+
<gazebo>
5+
<plugin filename="ign_ros2_control-system"
6+
name="ign_ros2_control::IgnitionROS2ControlPlugin">
7+
<parameters>$(find meta_bringup)/config/sentry.yaml</parameters>
8+
</plugin>
9+
</gazebo>
10+
11+
<gazebo>
12+
<plugin
13+
filename="libignition-gazebo-pose-publisher-system.so"
14+
name="ignition::gazebo::systems::PosePublisher">
15+
<publish_link_pose>true</publish_link_pose>
16+
<publish_sensor_pose>true</publish_sensor_pose>
17+
<publish_collision_pose>false</publish_collision_pose>
18+
<publish_visual_pose>false</publish_visual_pose>
19+
<publish_model_pose>true</publish_model_pose>
20+
<publish_nested_model_pose>true</publish_nested_model_pose>
21+
<use_pose_vector_msg>true</use_pose_vector_msg>
22+
<static_publisher>true</static_publisher>
23+
<static_update_frequency>-1</static_update_frequency>
24+
</plugin>
25+
</gazebo>
26+
</robot>
Lines changed: 108 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
<?xml version="1.0"?>
2+
<robot name="standard_omni" xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
4+
<xacro:property name="threshold" value="0.08" />
5+
<xacro:property name="pitch_lower_limit" value="-0.72" />
6+
<xacro:property name="pitch_upper_limit" value="0.457" />
7+
8+
<xacro:macro name="gimbal" params="">
9+
10+
<link name="yaw_gimbal">
11+
<inertial>
12+
<mass value="0.2" />
13+
<origin xyz="0 0 0" />
14+
<inertia ixx="4.878e-4" ixy="1.941e-5" ixz="2.44e-4" iyy="8.322e-4"
15+
iyz="-1.812e-5" izz="4.513e-4" />
16+
</inertial>
17+
<visual>
18+
<origin xyz="0 0 0" rpy="0 0 0" />
19+
<geometry>
20+
<mesh filename="file://$(find metav_description)/meshes/sentry/yaw_gimbal.stl"
21+
scale="0.001 0.001 0.001" />
22+
</geometry>
23+
<material name="silver">
24+
<color rgba="0.700 0.700 0.700 1.000" />
25+
</material>
26+
</visual>
27+
<collision>
28+
<origin xyz="0 0 0" rpy="0 0 0" />
29+
<geometry>
30+
<mesh filename="file://$(find metav_description)/meshes/sentry/yaw_gimbal.stl"
31+
scale="0.001 0.001 0.001" />
32+
</geometry>
33+
</collision>
34+
</link>
35+
36+
<joint name="yaw_gimbal_joint" type="continuous">
37+
<origin xyz="0 0 0.162"
38+
rpy="0 0 0" />
39+
<dynamics damping="0.0" friction="0.1" />
40+
<limit effort="1.2" velocity="31" />
41+
<parent link="base_link" />
42+
<child link="yaw_gimbal" />
43+
<axis xyz="0 0 1" />
44+
</joint>
45+
46+
<link name="supply_frame" />
47+
<joint name="supply_joint" type="fixed">
48+
<origin xyz="0 0 0" rpy="0 0 ${pi/3}" />
49+
<parent link="yaw_gimbal" />
50+
<child link="supply_frame" />
51+
</joint>
52+
53+
<link name="pitch_gimbal">
54+
<inertial>
55+
<mass value="0.644" />
56+
<origin xyz="0.029 0.000617 0.0376" />
57+
<inertia ixx="1.8216e-3" ixy="5.514e-6" ixz="1.58e-4" iyy="5.68e-3"
58+
iyz="-6.628e-6" izz="4.396e-3" />
59+
</inertial>
60+
<visual>
61+
<origin xyz="0 0 0" rpy="0 0 0" />
62+
<geometry>
63+
<mesh filename="file://$(find metav_description)/meshes/sentry/pitch_gimbal.stl"
64+
scale="0.001 0.001 0.001" />
65+
</geometry>
66+
<material name="silver">
67+
<color rgba="0.700 0.700 0.700 1.000" />
68+
</material>
69+
</visual>
70+
<collision>
71+
<origin xyz="0 0 0" rpy="0 0 0" />
72+
<geometry>
73+
<mesh filename="file://$(find metav_description)/meshes/sentry/pitch_gimbal.stl"
74+
scale="0.001 0.001 0.001" />
75+
</geometry>
76+
</collision>
77+
</link>
78+
79+
<joint name="pitch_gimbal_joint" type="revolute">
80+
<origin xyz="-0.029 0 0.257" rpy="0 0 0" />
81+
<dynamics damping="0.0" friction="0.1" />
82+
<limit effort="3." velocity="86" lower="${pitch_lower_limit}"
83+
upper="${pitch_upper_limit}" />
84+
<safety_controller k_position="100" k_velocity="0.1"
85+
soft_lower_limit="${pitch_lower_limit+threshold}"
86+
soft_upper_limit="${pitch_upper_limit-threshold}" />
87+
<parent link="yaw_gimbal" />
88+
<child link="pitch_gimbal" />
89+
<axis xyz="0 1 0 " />
90+
</joint>
91+
92+
</xacro:macro>
93+
94+
<xacro:macro name="gimbal_transmission"
95+
params="prefix mechanical_reduction offset motor_id">
96+
<joint name="${prefix}_gimbal_joint">
97+
<command_interface name="effort" />
98+
<state_interface name="position" />
99+
<state_interface name="velocity" />
100+
<state_interface name="effort" />
101+
<param name="motor_model">GM6020</param>
102+
<param name="motor_id">${motor_id}</param>
103+
<param name="mechanical_reduction">${mechanical_reduction}</param>
104+
<param name="offset">${offset}</param>
105+
</joint>
106+
</xacro:macro>
107+
108+
</robot>
Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
<?xml version="1.0"?>
2+
<robot name="standard_omni" xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
4+
<xacro:macro name="shooter" params="">
5+
6+
<!-- friction wheel 1 -->
7+
<link name="fric1_wheel">
8+
<inertial>
9+
<mass value="0.2" />
10+
<origin xyz="0 0 0" />
11+
<inertia ixx="0" ixy="0" ixz="0" iyy="0"
12+
iyz="0" izz="0" />
13+
</inertial>
14+
</link>
15+
16+
<joint name="fric1_shooter_joint" type="continuous">
17+
<origin xyz="0 0 0.162"
18+
rpy="0 0 0" />
19+
<dynamics damping="0.0" friction="0.1" />
20+
<limit effort="1.2" velocity="31" />
21+
<parent link="fric1_base" />
22+
<child link="fric1_wheel" />
23+
<axis xyz="0 0 1" />
24+
</joint>
25+
26+
<link name="fric1_base" />
27+
28+
<joint name="fric1_fixed_joint" type="fixed">
29+
<parent link="yaw_gimbal" />
30+
<child link="fric1_base" />
31+
</joint>
32+
33+
<!-- friction wheel 2 -->
34+
<link name="fric2_wheel">
35+
<inertial>
36+
<mass value="0.2" />
37+
<origin xyz="0 0 0" />
38+
<inertia ixx="0" ixy="0" ixz="0" iyy="0"
39+
iyz="0" izz="0" />
40+
</inertial>
41+
</link>
42+
43+
<joint name="fric2_shooter_joint" type="continuous">
44+
<origin xyz="0 0 0.162"
45+
rpy="0 0 0" />
46+
<dynamics damping="0.0" friction="0.1" />
47+
<limit effort="1.2" velocity="31" />
48+
<parent link="fric2_base" />
49+
<child link="fric2_wheel" />
50+
<axis xyz="0 0 1" />
51+
</joint>
52+
53+
<link name="fric2_base" />
54+
55+
<joint name="fric2_fixed_joint" type="fixed">
56+
<parent link="yaw_gimbal" />
57+
<child link="fric2_base" />
58+
</joint>
59+
60+
<!-- loader -->
61+
<link name="loader_wheel">
62+
<inertial>
63+
<mass value="0.2" />
64+
<origin xyz="0 0 0" />
65+
<inertia ixx="0" ixy="0" ixz="0" iyy="0"
66+
iyz="0" izz="0" />
67+
</inertial>
68+
</link>
69+
70+
<joint name="loader_shooter_joint" type="continuous">
71+
<origin xyz="0 0 0.162"
72+
rpy="0 0 0" />
73+
<dynamics damping="0.0" friction="0.1" />
74+
<limit effort="1.2" velocity="31" />
75+
<parent link="loader_base" />
76+
<child link="loader_wheel" />
77+
<axis xyz="0 0 1" />
78+
</joint>
79+
80+
<link name="loader_base" />
81+
82+
<joint name="loader_fixed_joint" type="fixed">
83+
<parent link="yaw_gimbal" />
84+
<child link="loader_base" />
85+
</joint>
86+
87+
88+
89+
</xacro:macro>
90+
91+
<xacro:macro name="shooter_transmission"
92+
params="prefix mechanical_reduction offset motor_id">
93+
<joint name="${prefix}_shooter_joint">
94+
<command_interface name="effort" />
95+
<state_interface name="position" />
96+
<state_interface name="velocity" />
97+
<state_interface name="effort" />
98+
<param name="motor_model">M2006</param>
99+
<param name="motor_id">${motor_id}</param>
100+
<param name="mechanical_reduction">${mechanical_reduction}</param>
101+
<param name="offset">${offset}</param>
102+
</joint>
103+
</xacro:macro>
104+
105+
</robot>
Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,80 @@
1+
<?xml version="1.0"?>
2+
<robot name="standard_omni" xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
4+
<xacro:arg name="is_simulation" default="true" />
5+
6+
<link name="base_footprint">
7+
</link>
8+
9+
<!-- raise the robot a bit higher to prevent it from stucking in the ground -->
10+
<joint name="joint_base_to_footprint" type="fixed">
11+
<origin rpy="0 0 0" xyz="0 0 1" />
12+
<parent link="base_footprint" />
13+
<child link="base_link" />
14+
</joint>
15+
16+
<xacro:include filename="$(find metav_description)/urdf/standard_omni/standard.chassis.xacro" />
17+
<xacro:if value="$(arg is_simulation)">
18+
<xacro:chassis roller_type="simple" />
19+
</xacro:if>
20+
<xacro:unless value="$(arg is_simulation)">
21+
<xacro:chassis roller_type="none" />
22+
</xacro:unless>
23+
24+
<xacro:include filename="$(find metav_description)/urdf/standard_omni/standard.gimbal.xacro" />
25+
<xacro:gimbal />
26+
27+
<xacro:include filename="$(find metav_description)/urdf/standard_omni/standard.shooter.xacro" />
28+
<xacro:shooter />
29+
30+
<xacro:include filename="$(find metav_description)/urdf/common/sensor_imu.xacro" />
31+
<xacro:sensor_imu connected_to="pitch_gimbal" imu_name="gimbal_imu" xyz="0 0 0.1"
32+
rpy="0 0 0" />
33+
34+
<xacro:include filename="$(find metav_description)/urdf/common/sensor_mid360.xacro" />
35+
<xacro:sensor_mid360 connected_to="yaw_gimbal" name="livox_frame" xyz="0.1687 0 0.11"
36+
rpy="0 0.2269 0" />
37+
38+
<xacro:unless value="$(arg is_simulation)">
39+
<ros2_control name="dji_motors" type="system">
40+
<hardware>
41+
<plugin>meta_hardware/MetaRobotDjiMotorNetwork</plugin>
42+
<param name="can_network_name">can1</param>
43+
</hardware>
44+
<xacro:wheel_transmission prefix="front" mechanical_reduction="20.0" motor_id="2" />
45+
<xacro:wheel_transmission prefix="right" mechanical_reduction="20.0" motor_id="3" />
46+
<xacro:wheel_transmission prefix="left" mechanical_reduction="20.0" motor_id="1" />
47+
<xacro:wheel_transmission prefix="back" mechanical_reduction="20.0" motor_id="4" />
48+
<xacro:gimbal_transmission prefix="yaw" mechanical_reduction="1.0" offset="0.25"
49+
motor_id="5" />
50+
<xacro:gimbal_transmission prefix="pitch" mechanical_reduction="1.0" offset="0.0"
51+
motor_id="6" />
52+
<xacro:shooter_transmission prefix="fric1" mechanical_reduction="1.0" offset="0.25"
53+
motor_id="5" />
54+
<xacro:shooter_transmission prefix="fric2" mechanical_reduction="-1.0" offset="0.0"
55+
motor_id="6" />
56+
<xacro:shooter_transmission prefix="loader" mechanical_reduction="36.0" offset="0.0"
57+
motor_id="7" />
58+
</ros2_control>
59+
</xacro:unless>
60+
61+
<xacro:if value="$(arg is_simulation)">
62+
<ros2_control name="standard_control" type="system">
63+
<hardware>
64+
<plugin>ign_ros2_control/IgnitionSystem</plugin>
65+
</hardware>
66+
<xacro:wheel_transmission prefix="front" mechanical_reduction="20.0" motor_id="2" />
67+
<xacro:wheel_transmission prefix="right" mechanical_reduction="20.0" motor_id="3" />
68+
<xacro:wheel_transmission prefix="left" mechanical_reduction="20.0" motor_id="1" />
69+
<xacro:wheel_transmission prefix="back" mechanical_reduction="20.0" motor_id="4" />
70+
<xacro:gimbal_transmission prefix="yaw" mechanical_reduction="1.0" offset="0.25"
71+
motor_id="9" />
72+
<xacro:gimbal_transmission prefix="pitch" mechanical_reduction="-1.0" offset="0.0"
73+
motor_id="10" />
74+
</ros2_control>
75+
</xacro:if>
76+
77+
<xacro:if value="$(arg is_simulation)">
78+
<xacro:include filename="$(find metav_description)/urdf/standard_omni/standard.gazebo.xacro" />
79+
</xacro:if>
80+
</robot>

execution/super_capacitor/include/super_capacitor/pacific_spirit_capacitor_driver.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ class PacificSpiritCapacitorDriver : public super_capacitor::SuperCapacitorBase
3535
void rx_loop(std::stop_token stop_token) override;
3636
std::unique_ptr<std::jthread> rx_thread_;
3737
double max_discharge_power_, base_power_, cap_energy_percentage_, cap_state_;
38+
double input_voltage_, capacitor_voltage_, input_current_, target_power_fb_;
3839
void tx() override;
3940

4041
};

0 commit comments

Comments
 (0)