Skip to content

Commit

Permalink
Fixed bug in REson plugin, updated to make norbit swathwidth more rea…
Browse files Browse the repository at this point in the history
…listic
  • Loading branch information
ivaughn committed Mar 19, 2020
1 parent 13278c4 commit 83666f5
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion src/dsros_reson_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ void dsrosRosResonSensor::UpdateChild(const gazebo::common::UpdateInfo &_info) {
pc_msg.height = 1;
pc_msg.width = num_beams;
sensor_msgs::PointCloud2Modifier modifier(pc_msg);
modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32, "y", 1,
modifier.setPointCloud2Fields(3, "x", 1, sensor_msgs::PointField::FLOAT32, "y", 1,
sensor_msgs::PointField::FLOAT32, "z", 1, sensor_msgs::PointField::FLOAT32);
modifier.resize(num_beams);
sensor_msgs::PointCloud2Iterator<float> iter_distance(pc_msg, "x");
Expand Down
8 changes: 4 additions & 4 deletions urdf/norbitWBMS_bathy_sim.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -41,17 +41,17 @@ POSSIBILITY OF SUCH DAMAGE.
<sensor name="${name}_sensor" type="ray">
<always_on>1</always_on>
<pose frame="">${xyz} ${rpy}</pose>
<visualize>false</visualize>
<visualize>true</visualize>
<update_rate>5</update_rate>
<ray>
<!-- These are our beams. They're limited equi-angular, but the distinction probably
doesn't matter -->
<scan>
<horizontal>
<samples>512</samples>
<samples>256</samples>
<resolution>0.40</resolution>
<min_angle>-${pi/180*100}</min_angle>
<max_angle>${pi/180*100}</max_angle>
<min_angle>-${pi/180*60}</min_angle>
<max_angle>${pi/180*60}</max_angle>
</horizontal>
</scan>
<range>
Expand Down

0 comments on commit 83666f5

Please sign in to comment.