diff --git a/config/hokuyo_utm30lx.yaml b/config/hokuyo_utm30lx.yaml new file mode 100644 index 0000000000000000000000000000000000000000..43feaefeef2526bdc36c8701a79e091343856ba9 --- /dev/null +++ b/config/hokuyo_utm30lx.yaml @@ -0,0 +1,20 @@ +pose_x: 0 +pose_y: 0 +pose_z: 0 +pose_roll: 0 +pose_pitch: 0 +pose_yaw: 0 +visualize: false +update_rate: 40 +samples: 1080 +resolution: 1 +min_angle: -2.36 +max_angle: 2.36 +range_min: 0.10 +range_max: 30.0 +range_resolution: 0.01 +noise_type: 'gaussian' +noise_mean: 0.0 +noise_stddev: 0.01 +topic_name: 'scan' +frame_name: 'scan_frame' \ No newline at end of file diff --git a/urdf/helena.xacro b/urdf/helena.xacro index ed877b50c22bc4face8b145abfea33b84c34fe34..653844323f512203fbb79a0294a9db646cd5b3af 100644 --- a/urdf/helena.xacro +++ b/urdf/helena.xacro @@ -10,7 +10,7 @@ <xacro:pioneer3 name="$(arg name)" resolution="low_res" sim_config="$(find iri_helena_gazebo)/config/helena_sim_config.yaml"> </xacro:pioneer3> - <xacro:helena_sensors name="$(arg name)" parent="$(arg name)_base_link"> + <xacro:helena_sensors name="$(arg name)" parent="base_link"> <origin xyz="0.0 0.0 0.27" rpy="0 0 3.14159" /> </xacro:helena_sensors> </robot> diff --git a/urdf/helena_sensors.xacro b/urdf/helena_sensors.xacro index 583249047a474949229274590c15a7c9d2f9a12a..31e1fd322aa9510e95e7eb1ef914cc9ffc00217c 100644 --- a/urdf/helena_sensors.xacro +++ b/urdf/helena_sensors.xacro @@ -5,7 +5,7 @@ <xacro:macro name="helena_sensors" params="name parent *origin"> - <link name="${name}_sensors_base"> + <link name="sensors_base"> <inertial> <mass value="4.00000000" /> <origin xyz="-0.02349208 0.00000000 0.20998619" rpy="0 0 0"/> @@ -29,19 +29,24 @@ </geometry> </collision> </link> + + <gazebo reference="sensors_base"> + <material>Gazebo/Grey</material> + </gazebo> - <joint name="joint_${parent}_to_${name}_sensors_base" type="fixed" > + + <joint name="joint_${parent}_to_sensors_base" type="fixed" > <parent link="${parent}"/> - <child link="${name}_sensors_base"/> + <child link="sensors_base"/> <xacro:insert_block name="origin" /> </joint> - <xacro:hokuyo_laser2d name="front" parent="${name}_sensors_base" resolution="low_res" model="utm30lx"> - <origin xyz="0.13121 -0.18921 0.063" rpy="0 0 0.79" /> + <xacro:hokuyo_laser2d name="rear" prefix="${name}" parent="sensors_base" mesh_resolution="low_res" model="utm30lx" config_file="$(find iri_helena_description)/config/hokuyo_utm30lx.yaml"> + <origin xyz="0.13121 -0.18921 0.063" rpy="0 0 -0.785" /> </xacro:hokuyo_laser2d> - <xacro:hokuyo_laser2d name="rear" parent="${name}_sensors_base" resolution="low_res" model="utm30lx"> - <origin xyz="-0.13121 +0.18921 0.063" rpy="0 0 2.63" /> + <xacro:hokuyo_laser2d name="front" prefix="${name}" parent="sensors_base" mesh_resolution="low_res" model="utm30lx" config_file="$(find iri_helena_description)/config/hokuyo_utm30lx.yaml"> + <origin xyz="-0.13121 +0.18921 0.063" rpy="0 0 2.36" /> </xacro:hokuyo_laser2d> </xacro:macro>