Why does accessing ModelPtr from WorldPtr cause VM to crash with modified gazebo_ray_sensor_plugin?
Hi All, I have made some modifications to gazebo_ray_sensor_plugin.cpp in ROS2 Foxy and I’m looking for some debugging help. The modifications work perfectly fine on my native Ubuntu 20.04 desktop, but crashes on a VirtualBox Ubuntu 20.04 VM I have on a Windows 10 machine. If I comment out the line in the code below where the ModelPtr is being assigned to model_, everything works great on the VM setup, no errors or crashes. However, I need the model pointer so that I can access a link's velocity. Any ideas why that line causes Gazebo to choke up and cause my VM to run out of memory?
void GazeboRosRaySensorPrivate::PublishPointCloud2(ConstLaserScanStampedPtr & _msg)
{
ignition::math::Vector3d v_link_rel_world_in_link {0,0,0};
if (calc_vel_flag_) {
// Get Model and Link
if(init_) {
model_ = world_->ModelByName(model_name_);
//link_ = model_->GetLink(frame_name_);
init_ = false;
}
// Get Link Relative Linear Velocity
//v_link_rel_world_in_link = link_->RelativeLinearVel();
}
// Convert Laser scan to PointCloud2
auto pc2 = gazebo_ros::Convert<sensor_msgs::msg::pointcloud2>(*_msg, min_intensity_,
calc_vel_flag_, v_link_rel_world_in_link);
// Set tf frame
pc2.header.frame_id = frame_name_;
// Publish output
boost::get<pointcloud2pub>(pub_)->publish(pc2);
}
The unmodified version of gazebo_ray_sensor_plugin.cpp can be found here: https://github.com/ros-simulation/gaz...
Go easy on me, I'm new to Gazebo and C++ in general.