ForceSensor.h
Go to the documentation of this file.
00001 /* 
00002  * Copyright (c) 2013 University of Jaume-I.
00003  * All rights reserved. This program and the accompanying materials
00004  * are made available under the terms of the GNU Public License v3.0
00005  * which accompanies this distribution, and is available at
00006  * http://www.gnu.org/licenses/gpl.html
00007  * 
00008  * Contributors:
00009  *     Mario Prats
00010  *     Javier Perez
00011  */
00012 
00013 #ifndef FORCESENSOR_H_
00014 #define FORCESENSOR_H_
00015 #include "SimulatedDevice.h"
00016 using namespace uwsim;
00017 
00018 class ForceSensor_Config : public SimulatedDeviceConfig
00019 {
00020 public:
00021   //XML members
00022   std::string target;
00023   double offsetp[3];
00024   double offsetr[3];
00025   //constructor
00026   ForceSensor_Config(std::string type_) :
00027       SimulatedDeviceConfig(type_)
00028   {
00029   }
00030 };
00031 
00032 //Driver/ROSInterface factory class
00033 class ForceSensor_Factory : public SimulatedDeviceFactory
00034 {
00035 public:
00036   //this is the only place the device/interface type is set
00037   ForceSensor_Factory(std::string type_ = "ForceSensor") :
00038       SimulatedDeviceFactory(type_)
00039   {
00040   }
00041   ;
00042 
00043   SimulatedDeviceConfig::Ptr processConfig(const xmlpp::Node* node, ConfigFile * config);
00044   bool applyConfig(SimulatedIAUV * auv, Vehicle &vehicleChars, SceneBuilder *sceneBuilder, size_t iteration);
00045   std::vector<boost::shared_ptr<ROSInterface> > getInterface(ROSInterfaceInfo & rosInterface,
00046                                                              std::vector<boost::shared_ptr<SimulatedIAUV> > & iauvFile);
00047 };
00048 
00049 //can be a sparate header file for actual implementation classes...
00050 
00051 #include "ConfigXMLParser.h"
00052 #include "ROSInterface.h"
00053 #include <ros/ros.h>
00054 #include <geometry_msgs/WrenchStamped.h>
00055 #include "BulletPhysics.h"
00056 
00057 //Driver class
00058 
00059 class ForceSensor : public SimulatedDevice
00060 {
00061   void applyPhysics(BulletPhysics * bulletPhysics);
00062   double lastTimeStep;
00063   int CBreference;
00064 public:
00065   BulletPhysics * physics;
00066   btRigidBody * copy, * btTarget;  //Rigid object copy with physical reaction
00067   osg::ref_ptr<osg::Node> target;
00068   double offsetp[3];
00069   osg::Matrixd offset; //We only need rotation as traslation goes to bullet directly
00070   int physicsApplied;
00071 
00072   ForceSensor(ForceSensor_Config * cfg, osg::ref_ptr<osg::Node> target);
00073   void getForceTorque(double force[3], double torque[3]);
00074 };
00075 
00076 
00077 
00078 //ROS publishers and subscribers work exactly as before, no subclassing is needed
00079 class ForceSensor_ROSPublisher : public ROSPublisherInterface
00080 {
00081   //this is just an example, use a pointer to SimulatedIAUV, if only ROSInterface is implemented
00082   //pointer to a device
00083   ForceSensor * dev;
00084 public:
00085   ForceSensor_ROSPublisher(ForceSensor *dev, std::string topic, int rate) :
00086       ROSPublisherInterface(topic, rate), dev(dev)
00087   {
00088   }
00089 
00090   void createPublisher(ros::NodeHandle &nh);
00091   void publish();
00092 
00093   ~ForceSensor_ROSPublisher()
00094   {
00095   }
00096 };
00097 
00098 #endif


uwsim
Author(s): Mario Prats , Javier Perez
autogenerated on Fri Aug 28 2015 13:28:58