// Services: bool ROS_server::displayText_service(vrep_skeleton_msg_and_srv::displayText::Request &req,vrep_skeleton_msg_and_srv::displayText::Response &res) { res.dialogHandle=simDisplayDialog("Message from a ROS node",req.textToDisplay.c_str(),sim_dlgstyle_message,NULL,NULL,NULL,NULL); return true; }
// This is the plugin messaging routine (i.e. V-REP calls this function very often, with various messages): VREP_DLLEXPORT void* v_repMessage(int message,int* auxiliaryData,void* customData,int* replyData) { // This is called quite often. Just watch out for messages/events you want to handle // Keep following 5 lines at the beginning and unchanged: //static bool refreshDlgFlag=true; int errorModeSaved; simGetIntegerParameter(sim_intparam_error_report_mode,&errorModeSaved); simSetIntegerParameter(sim_intparam_error_report_mode,sim_api_errormessage_ignore); void* retVal=NULL; // Here we can intercept many messages from V-REP (actually callbacks). Only the most important messages are listed here. // For a complete list of messages that you can intercept/react with, search for "sim_message_eventcallback"-type constants // in the V-REP user manual. if (message==sim_message_eventcallback_mainscriptabouttobecalled) { // The main script is about to be run (only called while a simulation is running (and not paused!)) // main script is called every dynamics calculation. tickRTCs(simGetSimulationTimeStep()); } if (message==sim_message_eventcallback_simulationabouttostart) { // Simulation is about to start simulatorClock.setSimulationTimeStep(simGetSimulationTimeStep()); //simulatorClock.setSimulationTime(simGetSimulationTime()); startRTCs(); } if (message == sim_message_eventcallback_menuitemselected) { simInt handle = auxiliaryData[0]; simInt state = auxiliaryData[1]; if (handle == robotItemHandle) { std::cout << "Robot Menu Selected" << std::endl; mainItemHandle = robotItemHandle; spawnRTCMethod = spawnRobotRTC; modelDlgHandle = simDisplayDialog("Input Robot Item", "Input Robot Model Name", sim_dlgstyle_input, "", NULL, NULL, NULL); } else if (handle == rangeItemHandle) { std::cout << "Range Menu Selected" << std::endl; mainItemHandle = rangeItemHandle; spawnRTCMethod = spawnRangeRTC; modelDlgHandle = simDisplayDialog("Input Item", "Input Range Model Name", sim_dlgstyle_input, "", NULL, NULL, NULL); } else if (handle == cameraItemHandle) { std::cout << "Camera Menu Selected" << std::endl; mainItemHandle = cameraItemHandle; spawnRTCMethod = spawnCameraRTC; modelDlgHandle = simDisplayDialog("Input Item", "Input Vision Sensor Model Name", sim_dlgstyle_input, "", NULL, NULL, NULL); } else if (handle == accelItemHandle) { std::cout << "Acceleration Menu Selected" << std::endl; mainItemHandle = accelItemHandle; spawnRTCMethod = spawnAccelerometerRTC; modelDlgHandle = simDisplayDialog("Input Item", "Input Accel Sensor Model Name", sim_dlgstyle_input, "", NULL, NULL, NULL); } else if (handle == gyroItemHandle) { std::cout << "Gyro Menu Selected" << std::endl; mainItemHandle = gyroItemHandle; spawnRTCMethod = spawnGyroRTC; modelDlgHandle = simDisplayDialog("Input Item", "Input Gyro Model Name", sim_dlgstyle_input, "", NULL, NULL, NULL); } else if (handle == depthItemHandle) { std::cout << "Depth Menu Selected" << std::endl; mainItemHandle = depthItemHandle; spawnRTCMethod = spawnDepthRTC; modelDlgHandle = simDisplayDialog("Input Item", "Input Depth Model Name", sim_dlgstyle_input, "", NULL, NULL, NULL); } else if (handle == objectItemHandle) { std::cout << "Object Menu Selected" << std::endl; mainItemHandle = objectItemHandle; spawnRTCMethod = spawnObjectRTC; modelDlgHandle = simDisplayDialog("Input Item", "Input Object Model Name", sim_dlgstyle_input, "", NULL, NULL, NULL); } } if (message == sim_message_eventcallback_refreshdialogs) { if (modelDlgHandle >= 0) { simInt ret = simGetDialogResult(modelDlgHandle); if (ret != sim_dlgret_still_open) { if (ret == sim_dlgret_ok) { char *buf = simGetDialogInput(modelDlgHandle); modelName = buf; std::cout << "Model Name is " << buf << std::endl; simReleaseBuffer(buf); argDlgHandle = simDisplayDialog("Input Argument of RTC", "Input Argument of createComponent method", sim_dlgstyle_input, "", NULL, NULL, NULL); modelDlgHandle = -1; } } } else if (argDlgHandle >= 0) { simInt ret = simGetDialogResult(argDlgHandle); if (ret != sim_dlgret_still_open) { if (ret == sim_dlgret_ok) { char *buf = simGetDialogInput(argDlgHandle); argument = buf; std::cout << "createComponent Argument is " << buf << std::endl; simReleaseBuffer(buf); argDlgHandle = -1; spawnRTCMethod(modelName, argument); } } } } if (message==sim_message_eventcallback_simulationended) { // Simulation just ended stopRTCs(); } simulatorClock.setSimulationTime(simGetSimulationTime()); message_pump(); // Keep following unchanged: simSetIntegerParameter(sim_intparam_error_report_mode,errorModeSaved); // restore previous settings return(retVal); }