vpROSRobot.h
Go to the documentation of this file.
00001 /****************************************************************************
00002  *
00003  * $Id: vpROSRobot.h 3778 2012-10-31 14:12:07Z fpasteau $
00004  *
00005  * This file is part of the ViSP software.
00006  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
00007  *
00008  * This software is free software; you can redistribute it and/or
00009  * modify it under the terms of the GNU General Public License
00010  * ("GPL") version 2 as published by the Free Software Foundation.
00011  * See the file LICENSE.txt at the root directory of this source
00012  * distribution for additional information about the GNU GPL.
00013  *
00014  * For using ViSP with software that can not be combined with the GNU
00015  * GPL, please contact INRIA about acquiring a ViSP Professional
00016  * Edition License.
00017  *
00018  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
00019  *
00020  * This software was developed at:
00021  * INRIA Rennes - Bretagne Atlantique
00022  * Campus Universitaire de Beaulieu
00023  * 35042 Rennes Cedex
00024  * France
00025  * http://www.irisa.fr/lagadic
00026  *
00027  * If you have questions regarding the use of this file, please contact
00028  * INRIA at visp@inria.fr
00029  *
00030  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
00031  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
00032  *
00033  *
00034  * Description:
00035  * vpRobot implementation for ROS middleware.
00036  *
00037  * Authors:
00038  * Francois Pasteau
00039  * Fabien Spindler
00040  *
00041  *****************************************************************************/
00042 
00043 
00044 #ifndef vpROSRobot_H
00045 #define vpROSRobot_H
00046 
00052 #include <visp/vpRobot.h>
00053 #include <ros/ros.h>
00054 #include <nav_msgs/Odometry.h>
00055 #include <geometry_msgs/Twist.h>
00056 
00062 class VISP_EXPORT vpROSRobot : public vpRobot
00063 {
00064   protected:
00065     ros::NodeHandle *n;
00066     ros::Publisher cmdvel;
00067     ros::Subscriber odom;
00068     ros::AsyncSpinner *spinner;
00069 
00070     bool isInitialized;
00071 
00072     vpQuaternionVector q;
00073     vpTranslationVector p;
00074     vpColVector pose_prev;
00075     vpColVector displacement;
00076     uint32_t _sec, _nsec;
00077     volatile bool odom_mutex;
00078     std::string _master_uri;
00079     std::string _topic_cmd;
00080     std::string _topic_odom;
00081     std::string _nodespace;
00082 
00083   private: // Set as private since not implemented
00084     void get_eJe(vpMatrix & eJe){}
00085 
00086     vpROSRobot(const vpROSRobot &robot);
00091     void get_fJe(vpMatrix & /*fJe*/) {}
00092 
00097     void getArticularDisplacement(vpColVector  & /*qdot*/) {};
00098 
00099 
00100     void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector & velocity);
00101     vpColVector getVelocity (const vpRobot::vpControlFrameType frame);
00102 
00107     void setPosition(const vpRobot::vpControlFrameType /*frame*/, const vpColVector &/*q*/) {};
00108     void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00109     void getCameraDisplacement(vpColVector & /*v*/);
00110 
00111   public:
00113     vpROSRobot() ;
00115     virtual ~vpROSRobot() ;
00116 
00117     void getDisplacement(const vpRobot::vpControlFrameType /*frame*/, vpColVector &/*q*/);
00118     void getDisplacement(const vpRobot::vpControlFrameType /*frame*/, vpColVector &/*q*/, struct timespec &timestamp);
00119     void getPosition(const vpRobot::vpControlFrameType /*frame*/, vpColVector &/*q*/);
00120 
00122     void init() ;
00123     void init(int argc, char **argv) ;
00124 
00125     void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel);
00126     void stopMotion();
00127     void setCmdVelTopic(std::string topic_name);
00128     void setOdomTopic(std::string topic_name);
00129     void setMasterURI(std::string master_uri);
00130     void setNodespace(std::string nodespace);
00131 } ;
00132 
00133 #endif
00134 
00135 
00136 


visp_ros
Author(s): Francois Pasteau, Fabien Spindler
autogenerated on Wed Aug 26 2015 16:44:33