Gazebo | Ignition | Community
Ask Your Question
1

how to retrieve contact data from engine (NOT MESSAGE)!

asked 2016-09-22 04:41:52 -0500

djou07 gravatar image

updated 2016-09-22 05:51:00 -0500

how to retrieve contact data directly from physic engine (not in a message).

I tried to use the map structure but this function also use messages.

sensors::SensorPtr sensor = sensors::SensorManager::Instance()->GetSensor(this->model->GetLink("0")->GetSensorName(0));

sensors::ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<sensors::ContactSensor>(sensor);

std::map<string, physics::Contact> contacts = contactSensor->GetContacts(this->contactSensor->GetCollisionName(0));

for (std::map<string, physics::Contact>::iterator iter = contacts.begin();iter != contacts.end(); ++iter)
{
       <<"count       " << iter->second.count <<endl
       <<"time        " << iter->second.time <<endl;
}

The probleme with messages, it may miss some data. I want that each time I run the simulation I get the same data sequence, but this is not the case. For instance look at this curves; data in the first run are different from the second even if its the same simulation image description image description

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-09-24 09:33:59 -0500

djou07 gravatar image

The solution is to use ContactManager classe

physics::ContactManager *contactManager =
 this->model->GetWorld()->GetPhysicsEngine()->GetContactManager();

for(int i=0; i<contactManager->GetContactCount(); i++)
{
    physics::Contact *contact = contactManager->GetContact(i);
    cout << "contact between "<<contact->collision1->GetLink()->GetName()<<" and "
    << contact-> collision2-> GetLink()->GetName() <<endl;          
}
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-09-22 04:41:52 -0500

Seen: 273 times

Last updated: Sep 24 '16