#include <rosbindings.h>
Public Member Functions | |
virtual void | Destroy () |
virtual int | main (const std::string &args) |
virtual void | Reset () |
ROSBindings (EnvironmentBasePtr penv) | |
virtual bool | SendCommand (std::ostream &sout, std::istream &sinput) |
virtual bool | SimulationStep (dReal fElapsedTime) |
virtual | ~ROSBindings () |
Protected Member Functions | |
virtual void | _threadrosfn () |
bool | SetLocalizationFromDetection (ostream &sout, istream &sinput) |
bool | SetLocalizationFromTF (ostream &sout, istream &sinput) |
boost::shared_ptr< ROSBindings > | shared_problem () |
boost::shared_ptr< ROSBindings const > | shared_problem_const () const |
virtual void | UpdateRobotFromDetection (const boost::shared_ptr< posedetection_msgs::ObjectDetection const > &topicmsg, RobotBasePtr probot, bool b2DLocalization) |
void | UpdateRobotFromTF (const ros::WallTimerEvent &event, RobotBasePtr probot, string mapframe, geometry_msgs::PoseStamped posestamped) |
Protected Attributes | |
bool | _bDestroyThread |
list< pair< RobotBasePtr, Transform > > | _listUpdatedRobots |
map< RobotBasePtr, boost::shared_ptr< void > > | _localizingrobots |
boost::mutex | _mutexrobots |
boost::shared_ptr < ros::NodeHandle > | _ros |
boost::shared_ptr < tf::TransformListener > | _tflistener |
boost::thread | _threadros |
Definition at line 41 of file rosbindings.h.
ROSBindings::ROSBindings | ( | EnvironmentBasePtr | penv | ) | [inline] |
Definition at line 44 of file rosbindings.h.
virtual ROSBindings::~ROSBindings | ( | ) | [inline, virtual] |
Definition at line 55 of file rosbindings.h.
virtual void ROSBindings::_threadrosfn | ( | ) | [inline, protected, virtual] |
Definition at line 124 of file rosbindings.h.
virtual void ROSBindings::Destroy | ( | ) | [inline, virtual] |
Definition at line 59 of file rosbindings.h.
virtual int ROSBindings::main | ( | const std::string & | args | ) | [inline, virtual] |
Definition at line 83 of file rosbindings.h.
virtual void ROSBindings::Reset | ( | ) | [inline, virtual] |
Definition at line 73 of file rosbindings.h.
virtual bool ROSBindings::SendCommand | ( | std::ostream & | sout, |
std::istream & | sinput | ||
) | [inline, virtual] |
Definition at line 111 of file rosbindings.h.
bool ROSBindings::SetLocalizationFromDetection | ( | ostream & | sout, |
istream & | sinput | ||
) | [inline, protected] |
Definition at line 241 of file rosbindings.h.
bool ROSBindings::SetLocalizationFromTF | ( | ostream & | sout, |
istream & | sinput | ||
) | [inline, protected] |
Definition at line 147 of file rosbindings.h.
boost::shared_ptr<ROSBindings> ROSBindings::shared_problem | ( | ) | [inline, protected] |
Definition at line 117 of file rosbindings.h.
boost::shared_ptr<ROSBindings const> ROSBindings::shared_problem_const | ( | ) | const [inline, protected] |
Definition at line 120 of file rosbindings.h.
virtual bool ROSBindings::SimulationStep | ( | dReal | fElapsedTime | ) | [inline, virtual] |
Definition at line 102 of file rosbindings.h.
virtual void ROSBindings::UpdateRobotFromDetection | ( | const boost::shared_ptr< posedetection_msgs::ObjectDetection const > & | topicmsg, |
RobotBasePtr | probot, | ||
bool | b2DLocalization | ||
) | [inline, protected, virtual] |
Definition at line 187 of file rosbindings.h.
void ROSBindings::UpdateRobotFromTF | ( | const ros::WallTimerEvent & | event, |
RobotBasePtr | probot, | ||
string | mapframe, | ||
geometry_msgs::PoseStamped | posestamped | ||
) | [inline, protected] |
Definition at line 132 of file rosbindings.h.
bool ROSBindings::_bDestroyThread [protected] |
Definition at line 361 of file rosbindings.h.
list<pair<RobotBasePtr,Transform> > ROSBindings::_listUpdatedRobots [protected] |
Definition at line 358 of file rosbindings.h.
map<RobotBasePtr,boost::shared_ptr<void> > ROSBindings::_localizingrobots [protected] |
Definition at line 357 of file rosbindings.h.
boost::mutex ROSBindings::_mutexrobots [protected] |
Definition at line 360 of file rosbindings.h.
boost::shared_ptr<ros::NodeHandle> ROSBindings::_ros [protected] |
Definition at line 356 of file rosbindings.h.
boost::shared_ptr<tf::TransformListener> ROSBindings::_tflistener [protected] |
Definition at line 355 of file rosbindings.h.
boost::thread ROSBindings::_threadros [protected] |
Definition at line 359 of file rosbindings.h.