Public Member Functions | Protected Attributes | Private Member Functions | List of all members
vpROSRobot Class Reference

Interface for robots based on ROS. More...

#include <vpROSRobot.h>

Inheritance diagram for vpROSRobot:
Inheritance graph
[legend]

Public Member Functions

void getDisplacement (const vpRobot::vpControlFrameType, vpColVector &)
 
void getDisplacement (const vpRobot::vpControlFrameType, vpColVector &, struct timespec &timestamp)
 
void getPosition (const vpRobot::vpControlFrameType, vpColVector &)
 
void init ()
 basic initialization More...
 
void init (int argc, char **argv)
 
void setCmdVelTopic (std::string topic_name)
 
void setMasterURI (std::string master_uri)
 
void setNodespace (std::string nodespace)
 
void setOdomTopic (std::string topic_name)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void stopMotion ()
 
 vpROSRobot ()
 constructor More...
 
virtual ~vpROSRobot ()
 destructor More...
 

Protected Attributes

std::string _master_uri
 
std::string _nodespace
 
uint32_t _nsec
 
uint32_t _sec
 
std::string _topic_cmd
 
std::string _topic_odom
 
ros::Publisher cmdvel
 
vpColVector displacement
 
bool isInitialized
 
ros::NodeHandlen
 
ros::Subscriber odom
 
volatile bool odom_mutex
 
vpTranslationVector p
 
vpColVector pose_prev
 
vpQuaternionVector q
 
ros::AsyncSpinnerspinner
 

Private Member Functions

void get_eJe (vpMatrix &eJe)
 
void get_fJe (vpMatrix &)
 
void getArticularDisplacement (vpColVector &)
 
void getCameraDisplacement (vpColVector &)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity)
 
void odomCallback (const nav_msgs::Odometry::ConstPtr &msg)
 
void setPosition (const vpRobot::vpControlFrameType, const vpColVector &)
 
 vpROSRobot (const vpROSRobot &robot)
 

Detailed Description

Interface for robots based on ROS.

Definition at line 62 of file vpROSRobot.h.

Constructor & Destructor Documentation

◆ vpROSRobot() [1/2]

vpROSRobot::vpROSRobot ( const vpROSRobot robot)
private

◆ vpROSRobot() [2/2]

vpROSRobot::vpROSRobot ( )

constructor

Definition at line 58 of file vpROSRobot.cpp.

◆ ~vpROSRobot()

vpROSRobot::~vpROSRobot ( )
virtual

destructor

Definition at line 75 of file vpROSRobot.cpp.

Member Function Documentation

◆ get_eJe()

void vpROSRobot::get_eJe ( vpMatrix &  eJe)
inlineprivate

Definition at line 84 of file vpROSRobot.h.

◆ get_fJe()

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.

◆ getArticularDisplacement()

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.

◆ getCameraDisplacement()

void vpROSRobot::getCameraDisplacement ( vpColVector &  )
private

◆ getDisplacement() [1/2]

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 252 of file vpROSRobot.cpp.

◆ getDisplacement() [2/2]

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 219 of file vpROSRobot.cpp.

◆ getPosition()

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 180 of file vpROSRobot.cpp.

◆ getVelocity() [1/2]

vpColVector vpROSRobot::getVelocity ( const vpRobot::vpControlFrameType  frame)
private

◆ getVelocity() [2/2]

void vpROSRobot::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector &  velocity 
)
private

◆ init() [1/2]

void vpROSRobot::init ( )

basic initialization

Basic initialisation

Definition at line 113 of file vpROSRobot.cpp.

◆ init() [2/2]

void vpROSRobot::init ( int  argc,
char **  argv 
)

Basic initialisation

Parameters
argc,argv: parameters of the main function

Definition at line 92 of file vpROSRobot.cpp.

◆ odomCallback()

void vpROSRobot::odomCallback ( const nav_msgs::Odometry::ConstPtr &  msg)
private

Definition at line 259 of file vpROSRobot.cpp.

◆ setCmdVelTopic()

void vpROSRobot::setCmdVelTopic ( std::string  topic_name)

Set the ROS topic name for cmdvel

Parameters
topic_namename of the topic.
Examples
tutorial-ros-pioneer-visual-servo.cpp, tutorial-ros-pioneer.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 305 of file vpROSRobot.cpp.

◆ setMasterURI()

void vpROSRobot::setMasterURI ( std::string  master_uri)

Set the URI for ROS Master

Parameters
master_uriURI of the master ("http://127.0.0.1:11311")

Definition at line 331 of file vpROSRobot.cpp.

◆ setNodespace()

void vpROSRobot::setNodespace ( std::string  nodespace)

Set the nodespace

Parameters
nodespaceNamespace of the connected camera (nodespace is appended to the all topic names)

Definition at line 344 of file vpROSRobot.cpp.

◆ setOdomTopic()

void vpROSRobot::setOdomTopic ( std::string  topic_name)

Set the ROS topic name for odom

Parameters
topic_namename of the topic.

Definition at line 318 of file vpROSRobot.cpp.

◆ setPosition()

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 106 of file vpROSRobot.h.

◆ setVelocity()

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 149 of file vpROSRobot.cpp.

◆ stopMotion()

void vpROSRobot::stopMotion ( )

Definition at line 285 of file vpROSRobot.cpp.

Member Data Documentation

◆ _master_uri

std::string vpROSRobot::_master_uri
protected

Definition at line 78 of file vpROSRobot.h.

◆ _nodespace

std::string vpROSRobot::_nodespace
protected

Definition at line 81 of file vpROSRobot.h.

◆ _nsec

uint32_t vpROSRobot::_nsec
protected

Definition at line 76 of file vpROSRobot.h.

◆ _sec

uint32_t vpROSRobot::_sec
protected

Definition at line 76 of file vpROSRobot.h.

◆ _topic_cmd

std::string vpROSRobot::_topic_cmd
protected

Definition at line 79 of file vpROSRobot.h.

◆ _topic_odom

std::string vpROSRobot::_topic_odom
protected

Definition at line 80 of file vpROSRobot.h.

◆ cmdvel

ros::Publisher vpROSRobot::cmdvel
protected

Definition at line 66 of file vpROSRobot.h.

◆ displacement

vpColVector vpROSRobot::displacement
protected

Definition at line 75 of file vpROSRobot.h.

◆ isInitialized

bool vpROSRobot::isInitialized
protected

Definition at line 70 of file vpROSRobot.h.

◆ n

ros::NodeHandle* vpROSRobot::n
protected

Definition at line 65 of file vpROSRobot.h.

◆ odom

ros::Subscriber vpROSRobot::odom
protected

Definition at line 67 of file vpROSRobot.h.

◆ odom_mutex

volatile bool vpROSRobot::odom_mutex
protected

Definition at line 77 of file vpROSRobot.h.

◆ p

vpTranslationVector vpROSRobot::p
protected

Definition at line 73 of file vpROSRobot.h.

◆ pose_prev

vpColVector vpROSRobot::pose_prev
protected

Definition at line 74 of file vpROSRobot.h.

◆ q

vpQuaternionVector vpROSRobot::q
protected

Definition at line 72 of file vpROSRobot.h.

◆ spinner

ros::AsyncSpinner* vpROSRobot::spinner
protected

Definition at line 68 of file vpROSRobot.h.


The documentation for this class was generated from the following files:


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33