Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
I
iri_pioneer3_description
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
labrobotica
ros
platforms
Pioneer3
iri_pioneer3_description
Commits
d63e9665
Commit
d63e9665
authored
8 years ago
by
Fernando Herrero
Browse files
Options
Downloads
Patches
Plain Diff
helena_description: updated xacro hokuyo/laser names and mesh
parent
47b1d587
No related branches found
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
meshes/uxm30lnp.stl
+0
-0
0 additions, 0 deletions
meshes/uxm30lnp.stl
urdf/helena.gazebo
+10
-10
10 additions, 10 deletions
urdf/helena.gazebo
urdf/helena.xacro
+8
-8
8 additions, 8 deletions
urdf/helena.xacro
with
18 additions
and
18 deletions
meshes/uxm30lnp.stl
0 → 100755
+
0
−
0
View file @
d63e9665
File added
This diff is collapsed.
Click to expand it.
urdf/helena.gazebo
+
10
−
10
View file @
d63e9665
...
@@ -120,9 +120,9 @@
...
@@ -120,9 +120,9 @@
</sensor>
</sensor>
</gazebo>
</gazebo>
<!--
hokuyo
-->
<!--
laser
-->
<gazebo
reference=
"front_
hokuyo
_link"
>
<gazebo
reference=
"front_
laser
_link"
>
<sensor
type=
"ray"
name=
"head_front_
hokuyo
_sensor"
>
<sensor
type=
"ray"
name=
"head_front_
laser
_sensor"
>
<pose>
0 0 0 0 0 0
</pose>
<pose>
0 0 0 0 0 0
</pose>
<visualize>
false
</visualize>
<visualize>
false
</visualize>
<update_rate>
40
</update_rate>
<update_rate>
40
</update_rate>
...
@@ -150,16 +150,16 @@
...
@@ -150,16 +150,16 @@
<stddev>
0.01
</stddev>
<stddev>
0.01
</stddev>
</noise>
</noise>
</ray>
</ray>
<plugin
name=
"gazebo_ros_head_
hokuyo
_controller"
filename=
"libgazebo_ros_laser.so"
>
<plugin
name=
"gazebo_ros_head_
laser
_controller"
filename=
"libgazebo_ros_laser.so"
>
<topicName>
/helena/lasers/front_scan
</topicName>
<topicName>
/helena/lasers/front_scan
</topicName>
<frameName>
/helena/front_
hokuyo
_link
</frameName>
<frameName>
/helena/front_
laser
_link
</frameName>
</plugin>
</plugin>
</sensor>
</sensor>
</gazebo>
</gazebo>
<!--
hokuyo
-->
<!--
laser
-->
<gazebo
reference=
"rear_
hokuyo
_link"
>
<gazebo
reference=
"rear_
laser
_link"
>
<sensor
type=
"ray"
name=
"head_rear_
hokuyo
_sensor"
>
<sensor
type=
"ray"
name=
"head_rear_
laser
_sensor"
>
<pose>
0 0 0 0 0 0
</pose>
<pose>
0 0 0 0 0 0
</pose>
<visualize>
false
</visualize>
<visualize>
false
</visualize>
<update_rate>
40
</update_rate>
<update_rate>
40
</update_rate>
...
@@ -187,9 +187,9 @@
...
@@ -187,9 +187,9 @@
<stddev>
0.01
</stddev>
<stddev>
0.01
</stddev>
</noise>
</noise>
</ray>
</ray>
<plugin
name=
"gazebo_ros_head_
hokuyo
_controller"
filename=
"libgazebo_ros_laser.so"
>
<plugin
name=
"gazebo_ros_head_
laser
_controller"
filename=
"libgazebo_ros_laser.so"
>
<topicName>
/helena/lasers/rear_scan
</topicName>
<topicName>
/helena/lasers/rear_scan
</topicName>
<frameName>
/helena/rear_
hokuyo
_link
</frameName>
<frameName>
/helena/rear_
laser
_link
</frameName>
</plugin>
</plugin>
</sensor>
</sensor>
</gazebo>
</gazebo>
...
...
This diff is collapsed.
Click to expand it.
urdf/helena.xacro
+
8
−
8
View file @
d63e9665
...
@@ -218,15 +218,15 @@
...
@@ -218,15 +218,15 @@
</inertial>
</inertial>
</link>
</link>
<joint
name=
"front_
hokuyo
_joint"
type=
"fixed"
>
<joint
name=
"front_
laser
_joint"
type=
"fixed"
>
<axis
xyz=
"0 1 0"
/>
<axis
xyz=
"0 1 0"
/>
<origin
xyz=
"0.2 0 0.05"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.2 0 0.05"
rpy=
"0 0 0"
/>
<parent
link=
"top_plate"
/>
<parent
link=
"top_plate"
/>
<child
link=
"front_
hokuyo
_link"
/>
<child
link=
"front_
laser
_link"
/>
</joint>
</joint>
<!-- Hokuyo Laser -->
<!-- Hokuyo Laser -->
<link
name=
"front_
hokuyo
_link"
>
<link
name=
"front_
laser
_link"
>
<collision>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<geometry>
...
@@ -237,7 +237,7 @@
...
@@ -237,7 +237,7 @@
<visual>
<visual>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<geometry>
<mesh
filename=
"package://helena_description/meshes/
hokuyo.dae
"
/>
<mesh
filename=
"package://helena_description/meshes/
uxm30lnp.stl
"
/>
</geometry>
</geometry>
</visual>
</visual>
...
@@ -248,15 +248,15 @@
...
@@ -248,15 +248,15 @@
</inertial>
</inertial>
</link>
</link>
<joint
name=
"rear_
hokuyo
_joint"
type=
"fixed"
>
<joint
name=
"rear_
laser
_joint"
type=
"fixed"
>
<axis
xyz=
"0 1 0"
/>
<axis
xyz=
"0 1 0"
/>
<origin
xyz=
"-0.2 0 0.05"
rpy=
"0 0 3.14159"
/>
<origin
xyz=
"-0.2 0 0.05"
rpy=
"0 0 3.14159"
/>
<parent
link=
"top_plate"
/>
<parent
link=
"top_plate"
/>
<child
link=
"rear_
hokuyo
_link"
/>
<child
link=
"rear_
laser
_link"
/>
</joint>
</joint>
<!-- Hokuyo Laser -->
<!-- Hokuyo Laser -->
<link
name=
"rear_
hokuyo
_link"
>
<link
name=
"rear_
laser
_link"
>
<collision>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<geometry>
...
@@ -267,7 +267,7 @@
...
@@ -267,7 +267,7 @@
<visual>
<visual>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<geometry>
<mesh
filename=
"package://helena_description/meshes/
hokuyo.dae
"
/>
<mesh
filename=
"package://helena_description/meshes/
uxm30lnp.stl
"
/>
</geometry>
</geometry>
</visual>
</visual>
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment