Interface for robots based on ROS.  
 More...
#include <vpROSRobot.h>
Interface for robots based on ROS. 
Definition at line 62 of file vpROSRobot.h.
 
  
  
      
        
          | vpROSRobot::vpROSRobot  | 
          ( | 
          const vpROSRobot &  | 
          robot | ) | 
           | 
         
       
   | 
  
private   | 
  
 
 
      
        
          | vpROSRobot::vpROSRobot  | 
          ( | 
           | ) | 
           | 
        
      
 
 
  
  
      
        
          | vpROSRobot::~vpROSRobot  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
virtual   | 
  
 
 
  
  
      
        
          | void vpROSRobot::get_eJe  | 
          ( | 
          vpMatrix &  | 
          eJe | ) | 
           | 
         
       
   | 
  
inlineprivate   | 
  
 
 
  
  
      
        
          | void vpROSRobot::get_fJe  | 
          ( | 
          vpMatrix &  | 
           | ) | 
           | 
         
       
   | 
  
inlineprivate   | 
  
 
Get the robot Jacobian expressed in the robot reference (or world) frame. 
- Warning
 - Not implemented. 
 
Definition at line 91 of file vpROSRobot.h.
 
 
  
  
      
        
          | void vpROSRobot::getArticularDisplacement  | 
          ( | 
          vpColVector &  | 
           | ) | 
           | 
         
       
   | 
  
inlineprivate   | 
  
 
Get a displacement expressed in the joint space between two successive position control. 
- Warning
 - Not implemented. 
 
Definition at line 97 of file vpROSRobot.h.
 
 
  
  
      
        
          | void vpROSRobot::getCameraDisplacement  | 
          ( | 
          vpColVector &  | 
           | ) | 
           | 
         
       
   | 
  
private   | 
  
 
 
      
        
          | void vpROSRobot::getDisplacement  | 
          ( | 
          const vpRobot::vpControlFrameType  | 
          frame,  | 
        
        
           | 
           | 
          vpColVector &  | 
          dis  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Get the robot displacement (frame has to be specified).
- Parameters
 - 
  
    | frame | : Control frame. For the moment, only vpRobot::REFERENCE_FRAME is implemented. | 
    | dis | : A 6 dimension vector that corresponds to the displacement of the robot since the last call to the function. | 
  
   
- Exceptions
 - 
  
    | vpRobotException::wrongStateError | : If the specified control frame is not supported.  | 
  
   
Definition at line 239 of file vpROSRobot.cpp.
 
 
      
        
          | void vpROSRobot::getDisplacement  | 
          ( | 
          const vpRobot::vpControlFrameType  | 
          frame,  | 
        
        
           | 
           | 
          vpColVector &  | 
          dis,  | 
        
        
           | 
           | 
          struct timespec &  | 
          timestamp  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Get the robot displacement (frame has to be specified).
- Parameters
 - 
  
    | frame | : Control frame. For the moment, only vpRobot::REFERENCE_FRAME is implemented. | 
    | dis | : A 6 dimension vector that corresponds to the displacement of the robot since the last call to the function. | 
    | timestamp | : timestamp of the last update of the displacement | 
  
   
- Exceptions
 - 
  
    | vpRobotException::wrongStateError | : If the specified control frame is not supported.  | 
  
   
Definition at line 211 of file vpROSRobot.cpp.
 
 
      
        
          | void vpROSRobot::getPosition  | 
          ( | 
          const vpRobot::vpControlFrameType  | 
          frame,  | 
        
        
           | 
           | 
          vpColVector &  | 
          pose  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Get the robot position (frame has to be specified).
- Parameters
 - 
  
    | frame | : Control frame. For the moment, only vpRobot::REFERENCE_FRAME is implemented. | 
    | pose | : A 6 dimension vector that corresponds to the position of the robot. | 
  
   
- Exceptions
 - 
  
    | vpRobotException::wrongStateError | : If the specified control frame is not supported.  | 
  
   
Definition at line 175 of file vpROSRobot.cpp.
 
 
  
  
      
        
          | void vpROSRobot::getVelocity  | 
          ( | 
          const vpRobot::vpControlFrameType  | 
          frame,  | 
         
        
           | 
           | 
          vpColVector &  | 
          velocity  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | vpColVector vpROSRobot::getVelocity  | 
          ( | 
          const vpRobot::vpControlFrameType  | 
          frame | ) | 
           | 
         
       
   | 
  
private   | 
  
 
 
      
        
          | void vpROSRobot::init  | 
          ( | 
           | ) | 
           | 
        
      
 
basic initialization 
Basic initialisation 
Definition at line 112 of file vpROSRobot.cpp.
 
 
      
        
          | void vpROSRobot::init  | 
          ( | 
          int  | 
          argc,  | 
        
        
           | 
           | 
          char **  | 
          argv  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Basic initialisation
- Parameters
 - 
  
    | argc,argv | : parameters of the main function  | 
  
   
Definition at line 93 of file vpROSRobot.cpp.
 
 
  
  
      
        
          | void vpROSRobot::odomCallback  | 
          ( | 
          const nav_msgs::Odometry::ConstPtr &  | 
          msg | ) | 
           | 
         
       
   | 
  
private   | 
  
 
 
      
        
          | void vpROSRobot::setCmdVelTopic  | 
          ( | 
          std::string  | 
          topic_name | ) | 
           | 
        
      
 
 
      
        
          | void vpROSRobot::setMasterURI  | 
          ( | 
          std::string  | 
          master_uri | ) | 
           | 
        
      
 
Set the URI for ROS Master
- Parameters
 - 
  
    | master_uri | URI of the master ("http://127.0.0.1:11311")  | 
  
   
Definition at line 311 of file vpROSRobot.cpp.
 
 
      
        
          | void vpROSRobot::setNodespace  | 
          ( | 
          std::string  | 
          nodespace | ) | 
           | 
        
      
 
Set the nodespace
- Parameters
 - 
  
    | nodespace | Namespace of the connected camera (nodespace is appended to the all topic names)  | 
  
   
Definition at line 323 of file vpROSRobot.cpp.
 
 
      
        
          | void vpROSRobot::setOdomTopic  | 
          ( | 
          std::string  | 
          topic_name | ) | 
           | 
        
      
 
Set the ROS topic name for odom
- Parameters
 - 
  
    | topic_name | name of the topic.  | 
  
   
Definition at line 298 of file vpROSRobot.cpp.
 
 
  
  
      
        
          | void vpROSRobot::setPosition  | 
          ( | 
          const vpRobot::vpControlFrameType  | 
          ,  | 
         
        
           | 
           | 
          const vpColVector &  | 
            | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
inlineprivate   | 
  
 
Set a displacement (frame has to be specified) in position control. 
- Warning
 - Not implemented. 
 
Definition at line 107 of file vpROSRobot.h.
 
 
      
        
          | void vpROSRobot::setVelocity  | 
          ( | 
          const vpRobot::vpControlFrameType  | 
          frame,  | 
        
        
           | 
           | 
          const vpColVector &  | 
          vel  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Set the velocity (frame has to be specified) that will be applied to the robot.
- Parameters
 - 
  
    | frame | : Control frame. For the moment, only vpRobot::REFERENCE_FRAME is implemented. | 
    | vel | : A 6 dimension vector that corresponds to the velocities to apply to the robot. | 
  
   
- Exceptions
 - 
  
    | vpRobotException::wrongStateError | : If the specified control frame is not supported.  | 
  
   
Definition at line 144 of file vpROSRobot.cpp.
 
 
      
        
          | void vpROSRobot::stopMotion  | 
          ( | 
           | ) | 
           | 
        
      
 
 
  
  
      
        
          | std::string vpROSRobot::_master_uri | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | std::string vpROSRobot::_nodespace | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | uint32_t vpROSRobot::_nsec | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | uint32_t vpROSRobot::_sec | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | std::string vpROSRobot::_topic_cmd | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | std::string vpROSRobot::_topic_odom | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | ros::Publisher vpROSRobot::cmdvel | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | vpColVector vpROSRobot::displacement | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | bool vpROSRobot::isInitialized | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | ros::NodeHandle* vpROSRobot::n | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | ros::Subscriber vpROSRobot::odom | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | volatile bool vpROSRobot::odom_mutex | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | vpTranslationVector vpROSRobot::p | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | vpColVector vpROSRobot::pose_prev | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | vpQuaternionVector vpROSRobot::q | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | ros::AsyncSpinner* vpROSRobot::spinner | 
         
       
   | 
  
protected   | 
  
 
 
The documentation for this class was generated from the following files: