Skip to content

Commit

Permalink
completed G.004 and G.005 (fixed launchfile world arg)
Browse files Browse the repository at this point in the history
  • Loading branch information
moribots committed Feb 24, 2020
1 parent 0028ecd commit 5fbbf0e
Show file tree
Hide file tree
Showing 9 changed files with 108 additions and 30 deletions.
8 changes: 8 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,14 @@ A.004

G.001

G.002

G.003

G.004

G.005

# Tasks Completed

0.000
Expand Down
2 changes: 1 addition & 1 deletion nuturtle_description/config/diff_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -38,4 +38,4 @@ motor_rot_max: 6.35492
motor_pwr_max: 265

# Maximum motor torque (stall) in Nm (9V: 1.0 | 11.1V: 1.4 | 12V: 1.5)
motor_torque_max: 1.0
motor_torque_max: 1.5
68 changes: 49 additions & 19 deletions nuturtle_description/rviz/ddrive_inspect.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ Panels:
- /TF1/Frames1
- /TF1/Tree1
- /Marker1
- /LaserScan1
Splitter Ratio: 0.5
Tree Height: 713
- Class: rviz/Selection
Expand All @@ -30,7 +31,7 @@ Panels:
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
SyncSource: LaserScan
Preferences:
PromptSaveOnExit: true
Toolbars:
Expand Down Expand Up @@ -81,18 +82,17 @@ Visualization Manager:
Show Axes: true
Show Names: true
Tree:
base_footprint:
base_link:
ball_caster:
{}
base_scan:
{}
rl_wheel:
{}
rr_wheel:
{}
odom:
{}
base_footprint:
base_link:
ball_caster:
{}
base_scan:
{}
rl_wheel:
{}
rr_wheel:
{}
Update Interval: 0
Value: true
- Alpha: 1
Expand Down Expand Up @@ -144,9 +144,39 @@ Visualization Manager:
Marker Topic: visualization_marker
Name: Marker
Namespaces:
{}
"": true
Queue Size: 100
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 0.15950000286102295
Min Value: 0.15950000286102295
Value: true
Axis: Z
Channel Name: intensity
Class: rviz/LaserScan
Color: 239; 41; 41
Color Transformer: FlatColor
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0
Min Color: 0; 0; 0
Min Intensity: 0
Name: LaserScan
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic: /scan
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Expand Down Expand Up @@ -175,25 +205,25 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 3.1841745376586914
Distance: 3.0793755054473877
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 1.2171825170516968
Y: 0.5935019850730896
Z: -0.1324193775653839
X: 0.9488404393196106
Y: 0.7157317996025085
Z: 0.11317954957485199
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.8047969937324524
Pitch: 1.5697963237762451
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 4.648577690124512
Yaw: 3.1235787868499756
Saved: ~
Window Geometry:
Displays:
Expand Down
4 changes: 2 additions & 2 deletions nuturtle_description/urdf/diff_drive.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@
friction="0"/>

<xacro:frame_joint name="base_scan" type="fixed"
origin_rpy="0 0 0" origin_xyz="0 0 ${H/2}"
parent="base_link" child="base_scan"/>
origin_rpy="0 0 0" origin_xyz="0 0 ${H/2 + r_bc}"
parent="base_link" child="base_scan"/> <!-- Add small offset to laser scanner -->

</robot>
5 changes: 3 additions & 2 deletions nuturtle_gazebo/launch/diff_drive_gazebo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,11 @@
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>

<arg name="world" default="$(find gazebo_ros)/launch/empty_world.launch"/>
<arg name="world" default="$(find nuturtlebot)/worlds/block.world"/>

<!-- We reuse the logic in empty_world.launch, changing only the name of the world to be launched -->
<include file="$(arg world)">
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world)" />
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="false"/>
Expand Down
6 changes: 4 additions & 2 deletions nuturtle_gazebo/launch/gazebo_waypoints.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,10 @@
<include file="$(find nuturtle_robot)/launch/follow_waypoints.launch">
<arg name="robot" value="-1"/>
</include>

<!-- TRY: $(find nuturtlebot)/worlds/block.world -->
<!-- TRY: $(find gazebo_ros)/launch/empty_world.launch -->
<arg name="world" default="$(find gazebo_ros)/launch/empty_world.launch"/>
<include file="$(find nuturtle_gazebo)/launch/diff_drive_gazebo.launch">
<arg name="world" value="$(arg world)"/>
</include>

</launch>
34 changes: 34 additions & 0 deletions nuturtle_gazebo/urdf/diff_drive.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -79,4 +79,38 @@
<!-- <fdir1>1 1 0</fdir1> --> <!-- friction direction -->
</gazebo>

<!-- Laser Scanner -->
<gazebo reference="base_scan">
<material>Gazebo/Orange</material>
<sensor type="ray" name="lds_lfcd_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>0.0</min_angle>
<max_angle>6.28319</max_angle>
</horizontal>
</scan>
<range>
<min>0.120</min>
<max>3.5</max>
<resolution>0.015</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lds_lfcd_controller" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>base_scan</frameName>
</plugin>
</sensor>
</gazebo>

</robot>
7 changes: 5 additions & 2 deletions nuturtle_robot/launch/basic_remote.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,14 @@
<machine name="turtlebot" address="turtlebot$(arg robot)" env-loader="/home/student/install/env.sh" user="student"/>
</group>



<node machine="turtlebot" pkg="rosserial_python" type="serial_node.py" name="serial_node">
<param name="port" value="/dev/ttyACM0"/>
<param name="baud" value="115200"/>
</node>

<node machine="turtlebot" pkg="hls_lfcd_lds_driver" type="hlds_laser_publisher" name="hlds_laser_publisher">
<param name="port" value="/dev/ttyUSB0"/>
<param name="frame_id" value="base_scan"/>
</node>

</launch>
4 changes: 2 additions & 2 deletions tsim/config/turtle_way.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
# waypoint x coords for pentagon
# waypoint_x: [3, 7, 7, 5, 3]
waypoint_x: [1, 1.5, 1.5, 1.25, 1]
waypoint_x: [0, 0.5, 0.5, 0.25, 0]

# waypoint y coords for pentagon
# waypoint_y: [2, 2, 7, 10, 7]
waypoint_y: [1, 1, 1.5, 2., 1.5]
waypoint_y: [0, 0, 0.5, 1., 0.5]

# frequency of control loop
frequency: 60.
Expand Down

0 comments on commit 5fbbf0e

Please sign in to comment.