Skip to content
GitLab
Menu
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
humanoides
bioloid_robot
Commits
e0406da9
Commit
e0406da9
authored
Aug 30, 2017
by
Sergi Hernandez
Browse files
Added a namespace to the sensor model to be used in both the darwin and the bioloid robots.
parent
4ccc17a8
Changes
3
Hide whitespace changes
Inline
Side-by-side
bioloid_description/urdf/sensors/cny70_ir.gazebo
View file @
e0406da9
...
...
@@ -2,7 +2,7 @@
<root
xmlns:xacro=
"http://ros.org/wiki/xacro"
>
<xacro:macro
name=
"cny70_ir_gazebo"
params=
"name update_rate fov min_range max_range"
>
<xacro:macro
name=
"cny70_ir_gazebo"
params=
"name
namespace
update_rate fov min_range max_range"
>
<gazebo
reference=
"${name}_ir_link"
>
<material>
Gazebo/Black
</material>
<gravity>
true
</gravity>
...
...
@@ -42,8 +42,8 @@
</range>
</ray>
<plugin
name=
"${name}_range_sensor"
filename=
"libgazebo_ros_range.so"
>
<frameName>
/
bioloid
/${name}_ir_link
</frameName>
<topicName>
/
bioloid
/sensors/range
</topicName>
<frameName>
/
${namespace}
/${name}_ir_link
</frameName>
<topicName>
/
${namespace}
/sensors/range
</topicName>
<radiation>
infrared
</radiation>
<fov>
${fov}
</fov>
<gaussianNoise>
0.0005
</gaussianNoise>
...
...
bioloid_description/urdf/sensors/cny70_ir.xacro
View file @
e0406da9
...
...
@@ -4,7 +4,7 @@
<xacro:include
filename=
"$(find bioloid_description)/urdf/sensors/cny70_ir.gazebo"
/>
<xacro:macro
name=
"cny70_ir"
params=
"name parent *origin update_rate fov min_range max_range"
>
<xacro:macro
name=
"cny70_ir"
params=
"name
namespace
parent *origin update_rate fov min_range max_range"
>
<!-- IR distance sensors -->
<link
name=
"${name}_ir_link"
>
<collision>
...
...
@@ -32,7 +32,7 @@
<child
link=
"${name}_ir_link"
/>
</joint>
<xacro:cny70_ir_gazebo
name=
"${name}"
update_rate=
"${update_rate}"
fov=
"${fov}"
min_range=
"${min_range}"
max_range=
"${max_range}"
/>
<xacro:cny70_ir_gazebo
name=
"${name}"
namespace=
"${namespace}"
update_rate=
"${update_rate}"
fov=
"${fov}"
min_range=
"${min_range}"
max_range=
"${max_range}"
/>
</xacro:macro>
</root>
bioloid_description/urdf/sensors/feet_ir.xacro
View file @
e0406da9
...
...
@@ -34,15 +34,15 @@
</joint>
<!-- sensor links -->
<xacro:cny70_ir
name=
"left_front_fwd"
parent=
"left_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<xacro:cny70_ir
name=
"left_front_fwd"
namespace=
"bioloid"
parent=
"left_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<origin
xyz=
"0.0085 -0.0055 0.038"
rpy=
"-1.5707 -1.5707 0"
/>
</xacro:cny70_ir>
<xacro:cny70_ir
name=
"left_front_dwn"
parent=
"left_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<xacro:cny70_ir
name=
"left_front_dwn"
namespace=
"bioloid"
parent=
"left_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<origin
xyz=
"0.0225 -0.012 0.0345"
rpy=
"0 0 -1.5707"
/>
</xacro:cny70_ir>
<xacro:cny70_ir
name=
"left_lateral_dwn"
parent=
"left_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<xacro:cny70_ir
name=
"left_lateral_dwn"
namespace=
"bioloid"
parent=
"left_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<origin
xyz=
"0.0575 -0.012 0.0065"
rpy=
"0 0 -1.5707"
/>
</xacro:cny70_ir>
...
...
@@ -74,15 +74,15 @@
</joint>
<!-- sensor links -->
<xacro:cny70_ir
name=
"right_front_fwd"
parent=
"right_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<xacro:cny70_ir
name=
"right_front_fwd"
namespace=
"bioloid"
parent=
"right_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<origin
xyz=
"-0.0085 -0.0055 0.038"
rpy=
"-1.5707 -1.5707 0"
/>
</xacro:cny70_ir>
<xacro:cny70_ir
name=
"right_front_dwn"
parent=
"right_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<xacro:cny70_ir
name=
"right_front_dwn"
namespace=
"bioloid"
parent=
"right_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<origin
xyz=
"-0.0225 -0.012 0.0345"
rpy=
"0 0 -1.5707"
/>
</xacro:cny70_ir>
<xacro:cny70_ir
name=
"right_lateral_dwn"
parent=
"right_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<xacro:cny70_ir
name=
"right_lateral_dwn"
namespace=
"bioloid"
parent=
"right_board_link"
update_rate=
"${update_rate}"
fov=
"0.05"
min_range=
"0.001"
max_range=
"${range}"
>
<origin
xyz=
"-0.0575 -0.012 0.0065"
rpy=
"0 0 -1.5707"
/>
</xacro:cny70_ir>
...
...
Sergi Hernandez
@shernand
mentioned in commit
a30adddb
·
Aug 30, 2017
mentioned in commit
a30adddb
mentioned in commit a30adddbcad225ee02bbb816d27ed50727e05a0a
Toggle commit list
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment