59 main( 
int argc, 
char **argv )
    78     ros::Publisher enableSyncMode_pub  = n->advertise< std_msgs::Bool >( 
"/enableSyncMode", 1 );
    79     ros::Publisher startSimTrigger_pub = n->advertise< std_msgs::Bool >( 
"/startSimulation", 1 );
    80     ros::Publisher stopSimTrigger_pub  = n->advertise< std_msgs::Bool >( 
"/stopSimulation", 1 );
    81     std_msgs::Bool trigger;
    82     std_msgs::Bool syncMode;
    83     std_msgs::Bool startStopSim;
    85     std::string simulationStepDone_topic_name = 
"/simulationStepDone";
    86     std::cout << 
"Subscribe to " << simulationStepDone_topic_name << std::endl;
    88     std::string simulationTime_topic_name = 
"/simulationTime";
    89     std::cout << 
"Subscribe to " << simulationTime_topic_name << std::endl;
    92     startStopSim.data = 
true;
    93     startSimTrigger_pub.publish( startStopSim );
    95     stopSimTrigger_pub.publish( startStopSim );
    98     enableSyncMode_pub.
publish( trigger );
    99     startSimTrigger_pub.publish( startStopSim );
   100     vpTime::wait( 1000 );
   104     double t_start     = vpTime::measureTimeSecond();
   105     double t_init      = vpTime::measureTimeMs();
   106     double t_init_prev = t_init;
   108     float t_simTime_start = 0, t_simTime = 0, t_simTime_prev = 0;
   111     t_simTime_start = t_simTime_prev = 
s_simTime;
   113     t_init_prev = vpTime::measureTimeMs();
   115     vpColVector q_init, q_final;
   117     std::cout << 
"q initial: " << 180. / M_PI * q_init.t() << 
" deg" << std::endl;
   119     while ( vpTime::measureTimeSecond() - t_start < 10 )
   122       t_init = vpTime::measureTimeMs();
   127       vpColVector qdot( 7, 0 );
   128       qdot[0] = vpMath::rad( 10 );
   130       vpTime::sleepMs( 50 );
   132       std::stringstream ss;
   133       ss << 
"Loop time: " << t_init - t_init_prev << 
" - " << t_simTime - t_simTime_prev << 
" ms";
   135       t_init_prev    = t_init;
   136       t_simTime_prev = t_simTime;
   138     std::cout << 
"Elapsed time: " << vpTime::measureTimeSecond() - t_start << 
" seconds - "   139               << t_simTime - t_simTime_start << std::endl;
   141     robot.
getPosition( vpRobot::JOINT_STATE, q_final );
   142     std::cout << 
"q final: " << 180 / M_PI * q_final.t() << 
" deg" << std::endl;
   143     std::cout << 
"Joint displacement: " << 180. / M_PI * ( q_final - q_init ).t() << 
" deg" << std::endl;
   145     stopSimTrigger_pub.publish( startStopSim );
   147   catch ( 
const vpException &e )
   149     std::cout << 
"ViSP exception: " << e.what() << std::endl;
   150     std::cout << 
"Stop the robot " << std::endl;
 void connect(const std::string &robot_ID="")
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setTopicJointState(const std::string &topic_jointState)
void publish(const boost::shared_ptr< M > &message) const
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
int main(int argc, char **argv)
void simTime_callback(const std_msgs::Float32 &msg)
static std::mutex s_mutex_ros
void setTopic_eMc(const std::string &topic_eMc)
void setVerbose(bool verbose)
void simStepDone_callback(const std_msgs::Bool &msg)
ROSCPP_DECL void spinOnce()
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
static bool s_simStepDone