simulation/gz_bridge: remove proceeding px4_ from servos in gazebo model (#20998)

Signed-off-by: Benjamin Perseghetti <bperseghetti@rudislabs.com>
This commit is contained in:
Benjamin Perseghetti 2023-01-24 19:56:11 -05:00 committed by GitHub
parent 684b4a4b8a
commit 60de5b3ea4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 14 additions and 14 deletions

View File

@ -491,7 +491,7 @@
</material>
</visual>
</link>
<joint name='px4_servo_0' type='revolute'>
<joint name='servo_0' type='revolute'>
<parent>base_link</parent>
<child>left_elevon</child>
<pose>-0.07 0.4 0.08 0.00 0 0.0</pose>
@ -511,7 +511,7 @@
</ode>
</physics>
</joint>
<joint name='px4_servo_1' type='revolute'>
<joint name='servo_1' type='revolute'>
<parent>base_link</parent>
<child>right_elevon</child>
<pose>-0.07 -0.4 0.08 0.00 0 0.0</pose>
@ -571,7 +571,7 @@
</ode>
</physics>
</joint>
<joint name='px4_servo_2' type='revolute'>
<joint name='servo_2' type='revolute'>
<parent>base_link</parent>
<child>elevator</child>
<pose> -0.5 0 0 0 0 0</pose>
@ -678,13 +678,13 @@
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>px4_servo_0</control_joint_name>
<control_joint_name>servo_0</control_joint_name>
<control_joint_rad_to_cl>-0.3</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>px4_servo_0</joint_name>
<sub_topic>px4_servo_0</sub_topic>
<joint_name>servo_0</joint_name>
<sub_topic>servo_0</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
@ -701,13 +701,13 @@
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>px4_servo_1</control_joint_name>
<control_joint_name>servo_1</control_joint_name>
<control_joint_rad_to_cl>-0.3</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>px4_servo_1</joint_name>
<sub_topic>px4_servo_1</sub_topic>
<joint_name>servo_1</joint_name>
<sub_topic>servo_1</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.05984281113</a0>
@ -760,13 +760,13 @@
<forward>1 0 0</forward>
<upward>0 0 1</upward>
<link_name>base_link</link_name>
<control_joint_name>px4_servo_2</control_joint_name>
<control_joint_name>servo_2</control_joint_name>
<control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
<joint_name>px4_servo_2</joint_name>
<sub_topic>px4_servo_2</sub_topic>
<joint_name>servo_2</joint_name>
<sub_topic>servo_2</sub_topic>
</plugin>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
<a0>0.0</a0>

View File

@ -35,9 +35,9 @@
bool GZMixingInterfaceServo::init(const std::string &model_name)
{
// /model/rascal_110_0/px4_servo_2
// /model/rascal_110_0/servo_2
for (int i = 0; i < 8; i++) {
std::string joint_name = "px4_servo_" + std::to_string(i);
std::string joint_name = "servo_" + std::to_string(i);
std::string servo_topic = "/model/" + model_name + "/" + joint_name;
//std::cout << "Servo topic: " << servo_topic << std::endl;
_servos_pub.push_back(_node.Advertise<gz::msgs::Double>(servo_topic));