Webots R2019和ROS使用筆記(機器人模擬軟體與作業系統)
安裝Webots R2019後,啟動:
選擇喜歡的模式:
如果使用整合顯示卡會彈出一個警告,可以忽略:
參考教程目錄進行學習。
編譯對應ROS功能包,進行ROS學習:
啟動webots和roscore後,然後使用rosrun嘗試每個demo:
#include "ros/ros.h"
#include <signal.h>
#include <std_msgs/String.h>
#include <sensor_msgs/Image.h>
#include <webots_ros/get_float.h>
#include <webots_ros/set_float.h>
#include <webots_ros/set_int.h>
#include <webots_ros/save_image.h>
#include <webots_ros/robot_get_device_list.h>
#include <webots_ros/range_finder_get_info.h>
#define TIME_STEP 32;
static int controllerCount;
static std::vector<std::string> controllerList;
static std::vector<float> imageRangeFinder;
ros::ServiceClient timeStepClient;
webots_ros::set_int timeStepSrv;
// catch names of the controllers availables on ROS network
void controllerNameCallback(const std_msgs::String::ConstPtr& name) {
controllerCount++;
controllerList.push_back(name->data);
ROS_INFO("Controller #%d: %s.",controllerCount,controllerList.back().c_str());
}
// get range image from the range-finder
void rangeFinderCallback(const sensor_msgs::Image::ConstPtr& image) {
int size = image->width * image->height;
imageRangeFinder.resize(size);
const float* depth_data = reinterpret_cast<const float*>(&image->data[0]);
for (int i = 0; i < size; ++i)
imageRangeFinder[i] = depth_data[i];
}
void quit(int sig) {
timeStepSrv.request.value = 0;
timeStepClient.call(timeStepSrv);
ROS_INFO("User stopped the 'catch_the_bird' node.");
ros::shutdown();
exit(0);
}
int main(int argc, char **argv) {
int wantedController = 0;
std::string controllerName, motorName, rangeFinderName;
std::vector<std::string> deviceList;
int width,height;
float i,step;
bool birdCatched = false;
if (argc != 1) {
ROS_INFO("Usage: $ example_catch_bird.");
return 1;
}
// create a node named 'catch_the_bird' on ROS network
ros::init(argc, argv, "catch_the_bird",ros::init_options::AnonymousName);
ros::NodeHandle n;
signal(SIGINT,quit);
// subscribe to the topic model_name to get the list of availables controllers
ros::Subscriber nameSub = n.subscribe("model_name", 100, controllerNameCallback);
while (controllerCount == 0 || controllerCount < nameSub.getNumPublishers()) {
ros::spinOnce();
ros::spinOnce();
ros::spinOnce();
}
ros::spinOnce();
// if there is more than one controller available, let the user choose
if (controllerCount == 1)
controllerName = controllerList[0];
else {
std::cout << "Choose the # of the controller you want to use:\n";
std::cin >> wantedController;
if (1 <= wantedController && wantedController <= controllerCount)
controllerName=controllerList[wantedController - 1];
else {
ROS_ERROR("Invalid number for controller choice.");
return 1;
}
}
// leave topic once it's not necessary anymore
nameSub.shutdown();
// call device_list service to get the list of the devices available on the controller and print it
// the device_list_srv object contains 2 members request and response. Their fields are described in the corresponding .srv file
ros::ServiceClient deviceListClient = n.serviceClient<webots_ros::robot_get_device_list>(controllerName+"/robot/get_device_list");
webots_ros::robot_get_device_list deviceListSrv;
if (deviceListClient.call(deviceListSrv))
deviceList = deviceListSrv.response.list;
else
ROS_ERROR("Failed to call service device_list.");
motorName = deviceList[0];
rangeFinderName = deviceList[1];
ros::ServiceClient rangeFinderGetInfoClient = n.serviceClient<webots_ros::range_finder_get_info>(controllerName+'/'+rangeFinderName+"/get_info");
webots_ros::range_finder_get_info rangeFinderGetInfoSrv;
if (rangeFinderGetInfoClient.call(rangeFinderGetInfoSrv)) {
width = rangeFinderGetInfoSrv.response.width;
height = rangeFinderGetInfoSrv.response.height;
ROS_INFO("Range-finder size is %d x %d.", width, height);
} else
ROS_ERROR("Failed to call service range_finder_get_info.");
// enable the range-finder
ros::ServiceClient enableRangeFinderClient = n.serviceClient<webots_ros::set_int>(controllerName+'/'+rangeFinderName+"/enable");
webots_ros::set_int enableRangeFinderSrv;
ros::Subscriber subRangeFinderRangeFinder;
enableRangeFinderSrv.request.value = 2 * TIME_STEP;
if (enableRangeFinderClient.call(enableRangeFinderSrv) && enableRangeFinderSrv.response.success) {
ROS_INFO("Range-finder enabled with sampling period %d.",enableRangeFinderSrv.request.value);
subRangeFinderRangeFinder = n.subscribe(controllerName+'/'+rangeFinderName+"/range_image",1,rangeFinderCallback);
// wait for the topics to be initialized
while (subRangeFinderRangeFinder.getNumPublishers() == 0);
} else
ROS_ERROR("Failed to call service enable for %s.",rangeFinderName.c_str());
ros::ServiceClient rangeFinderSaveImageClient = n.serviceClient<webots_ros::save_image>(controllerName+'/'+rangeFinderName+"/save_image");
webots_ros::save_image rangeFinderSaveImageSrv;
rangeFinderSaveImageSrv.request.filename = std::string(getenv("HOME")) + std::string("/bird_catched.png");
rangeFinderSaveImageSrv.request.quality = 100;
// enable motor
ros::ServiceClient motorSetPositionClient = n.serviceClient<webots_ros::set_float>(controllerName+'/'+motorName+"/set_position");
webots_ros::set_float motorSetPositionSrv;
motorSetPositionSrv.request.value = 0;
i = 0.2;
step = 0.025;
ros::ServiceClient motorGetTargetPositionClient = n.serviceClient<webots_ros::get_float>(controllerName+'/'+motorName+"/get_target_position");
webots_ros::get_float motorGetTargetPositionSrv;
// enable time_step
timeStepClient = n.serviceClient<webots_ros::set_int>(controllerName+"/robot/time_step");
timeStepSrv.request.value=TIME_STEP;
// main loop
while (!birdCatched && ros::ok()) {
motorSetPositionSrv.request.value = i;
motorSetPositionClient.call(motorSetPositionSrv);
if (!timeStepClient.call(timeStepSrv) || !timeStepSrv.response.success) {
ROS_ERROR("Failed to call next step with time_step service.");
exit(1);
}
motorGetTargetPositionClient.call(motorGetTargetPositionSrv);
if (i >= 3.14)
step = -0.025;
if (i <= -3.14)
step = 0.025;
i += step;
ros::spinOnce();
while (imageRangeFinder.size() < (width * height))
ros::spinOnce();
// check if it sees the bird and take a picture of the bird
if (imageRangeFinder[12 + (width * height / 4)] < 0.5) {
birdCatched = true;
if (rangeFinderSaveImageClient.call(rangeFinderSaveImageSrv) && rangeFinderSaveImageSrv.response.success == 1)
ROS_INFO("What a beautifull bird we found here!");
else
ROS_INFO("Failed to call service save_image to take a picture of the bird.");
}
}
timeStepSrv.request.value = 0;
timeStepClient.call(timeStepSrv);
n.shutdown();
}
鍵盤遙控機器人在環境中運動。
#include "ros/ros.h"
#include <webots_ros/Int32Stamped.h>
#include <webots_ros/set_float.h>
#include <webots_ros/set_int.h>
#include <webots_ros/robot_get_device_list.h>
#include <std_msgs/String.h>
#include <signal.h>
#include <stdio.h>
#define TIME_STEP 32
static int controllerCount;
static std::vector<std::string> controllerList;
static std::string controllerName;
static double lposition = 0;
static double rposition = 0;
ros::ServiceClient leftWheelClient;
webots_ros::set_float leftWheelSrv;
ros::ServiceClient rightWheelClient;
webots_ros::set_float rightWheelSrv;
ros::ServiceClient timeStepClient;
webots_ros::set_int timeStepSrv;
ros::ServiceClient enableKeyboardClient;
webots_ros::set_int enableKeyboardSrv;
// catch names of the controllers availables on ROS network
void controllerNameCallback(const std_msgs::String::ConstPtr& name) {
controllerCount++;
controllerList.push_back(name->data);
ROS_INFO("Controller #%d: %s.", controllerCount, controllerList.back().c_str());
}
void quit(int sig) {
enableKeyboardSrv.request.value = 0;
enableKeyboardClient.call(enableKeyboardSrv);
timeStepSrv.request.value = 0;
timeStepClient.call(timeStepSrv);
ROS_INFO("User stopped the 'keyboard_teleop' node.");
ros::shutdown();
exit(0);
}
void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr& value) {
int key = value->data;
int send = 0;
switch(key)
{
case 314:
lposition += -0.2;
rposition += 0.2;
send = 1;
break;
case 316:
lposition += 0.2;
rposition += -0.2;
send = 1;
break;
case 315:
lposition += 0.2;
rposition += 0.2;
send = 1;
break;
case 317:
lposition += -0.2;
rposition += -0.2;
send = 1;
break;
case 312:
ROS_INFO("END.");
quit(-1);
break;
default:
send = 0;
break;
}
leftWheelSrv.request.value = lposition;
rightWheelSrv.request.value = rposition;
if (send) {
if (!leftWheelClient.call(leftWheelSrv) || !rightWheelClient.call(rightWheelSrv) || !leftWheelSrv.response.success || !rightWheelSrv.response.success)
ROS_ERROR("Failed to send new position commands to the robot.");
}
return;
}
int main(int argc, char **argv) {
int wantedController = 0;
if (argc != 1) {
ROS_INFO("Keyboard_teleop doesn't take any arguments.");
return 1;
}
// create a node named 'keyboard_teleop' on ROS network
ros::init(argc, argv, "keyboard_teleop",ros::init_options::AnonymousName);
ros::NodeHandle n;
signal(SIGINT,quit);
// subscribe to the topic model_name to get the list of availables controllers
ros::Subscriber nameSub = n.subscribe("model_name", 100, controllerNameCallback);
while (controllerCount == 0 || controllerCount < nameSub.getNumPublishers()) {
ros::spinOnce();
ros::spinOnce();
ros::spinOnce();
}
ros::spinOnce();
// if there is more than one controller available, let the user choose
if (controllerCount == 1)
controllerName = controllerList[0];
else {
std::cout << "Choose the # of the controller you want to use:\n";
std::cin >> wantedController;
if (1 <= wantedController && wantedController <= controllerCount)
controllerName = controllerList[wantedController-1];
else {
ROS_ERROR("Invalid number for controller choice.");
return 1;
}
}
// leave topic once it's not necessary anymore
nameSub.shutdown();
leftWheelClient = n.serviceClient<webots_ros::set_float>(controllerName+"/left_wheel/set_position");
rightWheelClient = n.serviceClient<webots_ros::set_float>(controllerName+"/right_wheel/set_position");
timeStepClient = n.serviceClient<webots_ros::set_int>(controllerName+"/robot/time_step");
timeStepSrv.request.value = TIME_STEP;
enableKeyboardClient = n.serviceClient<webots_ros::set_int>(controllerName+"/keyboard/enable");
enableKeyboardSrv.request.value = TIME_STEP;
if (enableKeyboardClient.call(enableKeyboardSrv) && enableKeyboardSrv.response.success) {
ros::Subscriber sub_keyboard;
sub_keyboard = n.subscribe(controllerName+"/keyboard/key", 1, keyboardCallback);
while (sub_keyboard.getNumPublishers() == 0);
ROS_INFO("Keyboard enabled.");
ROS_INFO("Use the arrows in Webots window to move the robot.");
ROS_INFO("Press the End key to stop the node.");
// main loop
while (ros::ok()) {
ros::spinOnce();
if (!timeStepClient.call(timeStepSrv) || !timeStepSrv.response.success)
ROS_ERROR("Failed to call service time_step for next step.");
}
}
else
ROS_ERROR("Could not enable keyboard, success = %d.", enableKeyboardSrv.response.success);
enableKeyboardSrv.request.value = 0;
if (!enableKeyboardClient.call(enableKeyboardSrv) || !enableKeyboardSrv.response.success)
ROS_ERROR("Could not disable keyboard, success = %d.", enableKeyboardSrv.response.success);
timeStepSrv.request.value = 0;
timeStepClient.call(timeStepSrv);
ros::shutdown();
return(0);
}
e-puck巡執行緒序。
相關文章
- Windows系統使用Gazebo機器人模擬軟體和Cartographer(SLAM)Windows機器人SLAM
- 實現ARM+ROS(機器人作業系統)之執行ROS!ROS機器人作業系統
- Webots R2019地表最強的通用型機器人模擬器之一(開源了附下載地址)Web機器人
- ROS機器人作業系統資料與資訊(2018年11月)ROS機器人作業系統
- ROS機器人作業系統資料與資訊(2018年12月)ROS機器人作業系統
- ROS 2 Crystal Clemmys版機器人作業系統補充說明ROS機器人作業系統
- ROS 2 Crystal Clemmys版機器人作業系統安裝說明ROS機器人作業系統
- 還可以這樣實現ARM+ROS(機器人作業系統)ROS機器人作業系統
- 實現ARM+ROS(機器人作業系統)之環境搭建!ROS機器人作業系統
- 計算機作業系統——虛擬記憶體與實體記憶體計算機作業系統記憶體
- Webots和ROS的使用說明(譯)WebROS
- 作業系統引導和虛擬機器作業系統虛擬機
- 為什麼推薦使用Ubuntu 18.04 LTS學習機器人作業系統ROS 1和2Ubuntu機器人作業系統ROS
- 部落格關於ROS機器人作業系統內容調整說明ROS機器人作業系統
- 一文讀懂自動駕駛中的機器人作業系統ROS自動駕駛機器人作業系統ROS
- 常用的虛擬機器軟體有哪些?linux作業系統入門虛擬機Linux作業系統
- 作業系統的虛擬記憶體作業系統記憶體
- 作業-安裝虛擬機器以及CentOS作業系統虛擬機CentOS作業系統
- 作業系統筆記作業系統筆記
- 作業系統儲存器管理筆記作業系統筆記
- 軟體作業系統作業系統
- 作業系統的記憶體對齊機制學習筆記作業系統記憶體筆記
- 作業系統——記憶體管理學習筆記作業系統記憶體筆記
- ROS2GO+Cozmo=口袋機器人之人工智慧模擬和實驗平臺ROSGo機器人人工智慧
- ROS2GO之慕課《機器人作業系統入門》配置與使用(2018-2019-2)ROSGo機器人作業系統
- Keil的軟體模擬和硬體模擬
- 機器人作業系統ROS 1.0 和 2.0 發展規劃2018-2025(Open Robotics)譯機器人作業系統ROS
- Java作業系統課設之模擬程式管理系統Java作業系統
- 2.3.2 訊號量機制——作業系統筆記作業系統筆記
- Linux作業系統首次捆綁系統級虛擬化軟體Linux作業系統
- 清華大學-作業系統學習筆記(五)--- 虛擬記憶體技術作業系統筆記記憶體
- 作業系統學習筆記作業系統筆記
- 【工業機器人】工業機器人技術最新知識大全;工業機器人驅動與控制系統機器人
- 【2018.04.19 ROS機器人作業系統】機器人控制:運動規劃、路徑規劃及軌跡規劃簡介之一ROS機器人作業系統
- 作業系統-記憶體管理作業系統記憶體
- 作業系統——記憶體管理作業系統記憶體
- C、作業系統學習筆記作業系統筆記
- 虛擬作業系統作業系統