GazeboInterface.h
Go to the documentation of this file.
00001 #ifndef GAZEBOINTERFACE_H
00002 #define GAZEBOINTERFACE_H
00003 
00004 #include "RobotController.h"
00005 #include "nasa_r2_common_msgs/JointControl.h"
00006 #include "nasa_r2_common_msgs/JointStatus.h"
00007 #include "nasa_r2_common_msgs/JointCapability.h"
00008 
00009 #include "common/Plugin.hh"
00010 #include "common/Events.hh"
00011 
00012 #include <ros/ros.h>
00013 #include <sensor_msgs/JointState.h>
00014 #include <nasa_r2_common_msgs/JointCommand.h>
00015 
00016 namespace gazebo
00017 {
00018     class GazeboInterface : public ModelPlugin
00019     {
00020     public:
00021         GazeboInterface();
00022         ~GazeboInterface();
00023 
00024         virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00025         virtual void Init();
00026 
00027         // Called by the world update start event
00028         void update();
00029 
00030     private:
00031         // handle joint commands
00032         void commandJoints(const sensor_msgs::JointState::ConstPtr& msg);
00033 
00034         // handle joint control messages
00035         void controlJoints(const nasa_r2_common_msgs::JointControl::ConstPtr& msg);
00036 
00037         // traverse through yaml structure looking for the mapped values
00038         // param: structure to traverseB
00039         // valMap: returned map
00040         // searchKey: named value to find
00041         // ns: namespace to prepend
00042         // name: name of param
00043         void traverseParams(XmlRpc::XmlRpcValue param, std::map<std::string, XmlRpc::XmlRpcValue>& valMap, std::string searchKey = "",
00044                             std::string ns = "", std::string name = "");
00045 
00046         // get a double from double or int XmlRpcValue
00047         // returns false if type is neither double or int
00048         bool getDoubleVal(XmlRpc::XmlRpcValue& val, double& doubleVal);
00049 
00050         // Pointer to the model
00051         physics::ModelPtr modelPtr;
00052 
00053         // Pointer to the update event connection
00054         event::ConnectionPtr updateConnectionPtr;
00055 
00056         std::auto_ptr<RobotController> robotControllerPtr;
00057 
00058         // ros stuff
00059         std::auto_ptr<ros::NodeHandle> rosNodePtr;
00060         std::auto_ptr<ros::NodeHandle> paramsNodePtr;
00061 
00062         // joint commands
00063         std::string jointCommandsTopic;
00064         ros::Subscriber jointCommandsSub;
00065 
00066         // joint capabilities
00067         std::string jointCapabilitiesTopic;
00068         ros::Publisher jointCapabilitiesPub;
00069         std::map<std::string, std::pair<double, double> > jointLimits;
00070 
00071         // joint states
00072         std::string jointStatesTopic;
00073         ros::Publisher jointStatePub;
00074         double jointStatesStepTime;
00075         std::map<std::string, RobotController::JointState> jointStates;
00076 
00077         // joint commandRefs
00078         std::string jointCommandRefsTopic;
00079         ros::Publisher jointCommandRefsPub;
00080         std::map<std::string, RobotController::JointState> jointCommandRefs;
00081 
00082         // joint status
00083         bool advancedMode;
00084         std::string jointControlTopic;
00085         ros::Subscriber jointControlSub;
00086         std::string jointStatusTopic;
00087         ros::Publisher jointStatusPub;
00088         double jointStatusStepTime;
00089 
00090         common::Time prevStatesUpdateTime;
00091         common::Time prevStatusUpdateTime;
00092     };
00093 }
00094 
00095 #endif


gazebo_interface
Author(s): rctaylo2
autogenerated on Mon Oct 6 2014 02:44:38