Skip to content

Commit

Permalink
Removed unnecessary wrappers
Browse files Browse the repository at this point in the history
  • Loading branch information
arturmiller committed Jan 13, 2019
1 parent 1ef7669 commit dc7b9d7
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 86 deletions.
79 changes: 2 additions & 77 deletions include/alpyca/sim/contact_sensor_wrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,81 +19,6 @@ namespace py = pybind11;

namespace gazebo
{
class ContactWrapper
{
public:
ContactWrapper(msgs::Contact _contact) : contact(_contact)
{
}

std::vector<double> depth()
{
std::vector<double> dep = {};
for (unsigned int i = 0; i < contact.position_size(); ++i)
{
dep.push_back(contact.depth(i));
}

return dep;
}

const::std::string & collision1()
{
return contact.collision1();
}

const::std::string & collision2()
{
return contact.collision2();
}

std::vector<gazebo::msgs::Vector3d> position()
{
std::vector<gazebo::msgs::Vector3d> pos = {};
for (unsigned int i = 0; i < contact.position_size(); ++i)
{
pos.push_back(contact.position(i));
}

return pos;
}

std::vector<gazebo::msgs::Vector3d> normal()
{
std::vector<gazebo::msgs::Vector3d> norm = {};
for (unsigned int i = 0; i < contact.position_size(); ++i)
{
norm.push_back(contact.normal(i));
}

return norm;
}

private:
msgs::Contact contact;
};

class ContactsWrapper
{
public:
ContactsWrapper(msgs::Contacts _contacts) : contacts(_contacts)
{
}

ContactWrapper contact(int index)
{
if(index >= contacts.contact_size())
{
throw py::index_error();
}

return contacts.contact(index);
}

private:
msgs::Contacts contacts;
};

class ContactSensorWrapper : public SensorWrapper
{
public:
Expand All @@ -102,9 +27,9 @@ namespace gazebo
parentSensor = std::dynamic_pointer_cast<sensors::ContactSensor>(_sensor);
}

ContactsWrapper Contacts()
msgs::Contacts Contacts()
{
return ContactsWrapper(parentSensor->Contacts());
return parentSensor->Contacts();
}

private:
Expand Down
53 changes: 44 additions & 9 deletions src/alpyca/sim/py_contact_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,49 @@ namespace gazebo
.def_property_readonly("y", &gazebo::msgs::Vector3d::y)
.def_property_readonly("z", &gazebo::msgs::Vector3d::z);

py::class_<ContactWrapper>(m, "PyContact")
.def_property_readonly("collision1", &ContactWrapper::collision1)
.def_property_readonly("collision2", &ContactWrapper::collision2)
.def_property_readonly("position", &ContactWrapper::position)
.def_property_readonly("normal", &ContactWrapper::normal)
.def_property_readonly("depth", &ContactWrapper::depth);

py::class_<ContactsWrapper>(m, "PyContacts")
.def("__getitem__", &ContactsWrapper::contact);
py::class_<msgs::Contact>(m, "PyContact")
.def_property_readonly("collision1", &msgs::Contact::collision1)
.def_property_readonly("collision2", &msgs::Contact::collision2)
.def_property_readonly("depth", [](msgs::Contact *contact) -> std::vector<double>
{
std::vector<double> dep = {};
for (unsigned int i = 0; i < contact->position_size(); ++i)
{
dep.push_back(contact->depth(i));
}

return dep;
})
.def_property_readonly("position", [](msgs::Contact *contact) -> std::vector<gazebo::msgs::Vector3d>
{
std::vector<gazebo::msgs::Vector3d> pos = {};
for (unsigned int i = 0; i < contact->position_size(); ++i)
{
pos.push_back(contact->position(i));
}

return pos;
})
.def_property_readonly("normal", [](msgs::Contact *contact) -> std::vector<gazebo::msgs::Vector3d>
{
std::vector<gazebo::msgs::Vector3d> norm = {};
for (unsigned int i = 0; i < contact->position_size(); ++i)
{
norm.push_back(contact->normal(i));
}

return norm;
});

py::class_<msgs::Contacts>(m, "PyContacts")
.def("__getitem__", [](msgs::Contacts *contacts, int index) -> msgs::Contact
{
if(index >= contacts->contact_size())
{
throw py::index_error();
}

return contacts->contact(index);
});
}
}

0 comments on commit dc7b9d7

Please sign in to comment.