Gazebo | Ignition | Community
Ask Your Question
0

How to get the name of a entity a ray or a ray sensor collides with?

asked 2016-04-01 05:23:21 -0500

Hans-Joachim Krauch gravatar image

In my sensor plugin, I have a ray sensor which casts a single ray. From this ray, I would like to get the name of the entity with which the ray intersects.

I have a working workaround by creating a test_ray (physics::RayShapePtr) and calling test_ray->GetIntersection() every time my ray measures a finite distance. However, it doesn't feel like the right way to do and furthermore, I get occasional segfaults which are caused somehow by underlying collision checks of the test_ray->GetIntersection() call.

Is there a better way to get the entity name?

In my plugin I have access to the parent ray sensor which is of type sensors::RaySensorPtr. From the parent sensor I can access the LaserShape (physics::MultiRayShapePtr), but apparently not the single ray (tried getChild(0) already).

Cheers,

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-04-01 11:42:43 -0500

nkoenig gravatar image

I'm currently looking at Gazebo default, which may not match with your version of gazebo. I think you can use the following API calls:

  1. physics::MultiRayShapePtr RaySensor::LaserShape() const
  2. RayShapePtr MultiRayShape::Ray(const unsigned int _rayIndex) const
  3. void RayShape::GetIntersection(double &_dist, std::string &_entity)

An implementation might look like:

RaySensorPtr mySensor;
double dist;
std::string entity;

// Should check these pointers for NULL
mySensor->LaserShape()->Ray(0)->GetIntersection(dist, entity);

std::cout << "My ray intersected entity[" << entity << "] at a distance of[" << dist << "]\n";
edit flag offensive delete link more

Comments

Ah ok, I see you have added this functionality in Gazebo 7. I'm bound to 6.5 however (forgot to mention this), but it helps me anyway, thanks a lot!

Hans-Joachim Krauch gravatar imageHans-Joachim Krauch ( 2016-04-04 02:16:38 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-04-01 05:23:21 -0500

Seen: 1,311 times

Last updated: Apr 01 '16