Skip to content

Commit

Permalink
Custom world with objects, Camera to A1 model but URDF/SDF not generated
Browse files Browse the repository at this point in the history
  • Loading branch information
DanielChaseButterfield committed Jun 26, 2024
1 parent 258a061 commit dce8b86
Show file tree
Hide file tree
Showing 8 changed files with 1,568 additions and 5 deletions.
6 changes: 3 additions & 3 deletions external/teleop_twist_joy/config/pro_controller.config.yaml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
axis_linear: 1 # Left thumb stick vertical
scale_linear: 1.5
scale_linear_turbo: 2.4
scale_linear: 1.0
scale_linear_turbo: 1.0

axis_angular: 0 # Left thumb stick horizontal
scale_angular: 1.5
scale_angular: 1.0

enable_button: 7 # ZR
enable_turbo_button: 5 # R
6 changes: 6 additions & 0 deletions quad_simulator/a1_description/xacro/const.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,12 @@
<xacro:property name="toe_stiffness" value="30000.0"/>
<xacro:property name="toe_damping" value="1000.0"/>

<!-- Camera values-->
<xacro:property name="camera_offset_x" value="0.2"/>
<xacro:property name="camera_offset_y" value="0.02"/>
<xacro:property name="camera_offset_z" value="0.00"/>
<xacro:property name="camera_size" value="0.02"/>

<!-- kinematic value -->
<xacro:property name="thigh_offset" value="0.0838"/>
<xacro:property name="thigh_length" value="0.2"/>
Expand Down
43 changes: 42 additions & 1 deletion quad_simulator/a1_description/xacro/gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
<visualize>true</visualize>
<topic>__default_topic__</topic>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<topicName>trunk_imu</topicName>
<topicName>state/imu</topicName>
<bodyName>imu_link</bodyName>
<updateRateHZ>1000.0</updateRateHZ>
<gaussianNoise>0.0</gaussianNoise>
Expand All @@ -61,6 +61,47 @@
</sensor>
</gazebo>

<!-- Camera -->
<gazebo reference="camera_link">
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>a1/camera1</cameraName>
<imageTopicName>camera/image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>

<!-- Foot contacts. -->
<!-- <gazebo reference="lower0">
<sensor name="FR_foot_contact" type="contact">
Expand Down
31 changes: 31 additions & 0 deletions quad_simulator/a1_description/xacro/robot.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,37 @@
</collision>
</link>

<!--Camera-->
<joint name="camera_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${camera_offset_x} ${camera_offset_y} ${camera_offset_z}" rpy="0 0 0"/>
<parent link="trunk"/>
<child link="camera_link"/>
</joint>

<link name="camera_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_size} ${camera_size} ${camera_size}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_size} ${camera_size} ${camera_size}"/>
</geometry>
<material name="red"/>
</visual>

<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>

<!--FL-->
<xacro:leg suffix="0" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True"
hipJointName="0" kneeJointName="1" abductionJointName="8">
Expand Down
Binary file not shown.
Binary file not shown.
Loading

0 comments on commit dce8b86

Please sign in to comment.