From c157c22a617bd84e5bf424f15220f8d4428e0c0b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Okan=20A=C5=9F=C4=B1k?= Date: Mon, 27 Nov 2017 00:15:23 +0300 Subject: [PATCH] add visual states examples --- .../obstacleAvoidanceCpp.xml | 87 +++++++++++++++++ .../obstacleAvoidancePython.xml | 84 +++++++++++++++++ .../obstacleAvoidanceCpp.xml | 87 +++++++++++++++++ .../obstacleAvoidancePython.xml | 84 +++++++++++++++++ .../obstacleAvoidanceCpp.xml | 94 +++++++++++++++++++ .../obstacleAvoidancePython.xml | 91 ++++++++++++++++++ 6 files changed, 527 insertions(+) create mode 100644 src/examples/visualStates/jderobot_comm/ice/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml create mode 100644 src/examples/visualStates/jderobot_comm/ice/obstacleAvoidancePython/obstacleAvoidancePython.xml create mode 100644 src/examples/visualStates/jderobot_comm/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml create mode 100644 src/examples/visualStates/jderobot_comm/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml create mode 100644 src/examples/visualStates/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml create mode 100644 src/examples/visualStates/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml diff --git a/src/examples/visualStates/jderobot_comm/ice/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml b/src/examples/visualStates/jderobot_comm/ice/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml new file mode 100644 index 000000000..802907177 --- /dev/null +++ b/src/examples/visualStates/jderobot_comm/ice/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml @@ -0,0 +1,87 @@ + + + + + + ice + myMotors + + Motors + localhost + 9001 + Motors + + + ice + myLaser + + Laser + localhost + 9001 + Laser + + + + + + 0.0 + 0.0 + root + + void calculate_obstacle() { + JdeRobotTypes::LaserData laserData = myLaser->getLaserData(); + for (int i = 0; i < laserData.values.size(); i++) { + if (laserData.values[i] < obstacle_threshold) { + is_obstacle = true; + return; + } + } + is_obstacle = false; +} + float obstacle_threshold = 0.4; +bool is_obstacle = false; + 100 + + 845.0 + 970.0 + move + interfaces->myMotors->sendV(0.4); +interfaces->myMotors->sendW(0); + + + 100 + + 1 + interfaces->calculate_obstacle(); +return interfaces->is_obstacle; + 931.0 + 884.0 + obstacle + 1 + 2 + + + + + 1023.0 + 981.0 + avoid + interfaces->myMotors->sendV(0); +interfaces->myMotors->sendW(0.1); + + + 100 + + 1 + interfaces->calculate_obstacle(); +return !interfaces->is_obstacle; + 927.0 + 1056.0 + no obstacle + 2 + 1 + + + + + diff --git a/src/examples/visualStates/jderobot_comm/ice/obstacleAvoidancePython/obstacleAvoidancePython.xml b/src/examples/visualStates/jderobot_comm/ice/obstacleAvoidancePython/obstacleAvoidancePython.xml new file mode 100644 index 000000000..751d58518 --- /dev/null +++ b/src/examples/visualStates/jderobot_comm/ice/obstacleAvoidancePython/obstacleAvoidancePython.xml @@ -0,0 +1,84 @@ + + + + + + ice + myMotors + + Motors + localhost + 9001 + Motors + + + ice + myLaser + + Laser + localhost + 9001 + Laser + + + + + + 0.0 + 0.0 + root + + def calculate_obstacle(self): + threshold_value = 0.4 + laserData = self.myLaser.getLaserData() + for val in laserData.values: + if val < threshold_value: + self.is_obstacle = True + return + self.is_obstacle = False + self.is_obstacle = False + 100 + + 845.0 + 970.0 + move + self.interfaces.myMotors.sendV(0.4) +self.interfaces.myMotors.sendW(0) + + + 100 + + 1 + self.interfaces.calculate_obstacle() +return self.interfaces.is_obstacle + 931.0 + 884.0 + obstacle + 1 + 2 + + + + + 1023.0 + 981.0 + avoid + self.interfaces.myMotors.sendV(0) +self.interfaces.myMotors.sendW(0.1) + + + 100 + + 1 + self.interfaces.calculate_obstacle() +return not self.interfaces.is_obstacle + 927.0 + 1056.0 + no obstacle + 2 + 1 + + + + + diff --git a/src/examples/visualStates/jderobot_comm/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml b/src/examples/visualStates/jderobot_comm/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml new file mode 100644 index 000000000..30267557f --- /dev/null +++ b/src/examples/visualStates/jderobot_comm/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml @@ -0,0 +1,87 @@ + + + + + + ros + myMotors + /turtlebotROS/mobile_base/commands/velocity + + + + Motors + + + ros + myLaser + /turtlebotROS/laser/scan + + + + Laser + + + + + + 0.0 + 0.0 + root + + void calculate_obstacle() { + JdeRobotTypes::LaserData laserData = myLaser->getLaserData(); + for (int i = 0; i < laserData.values.size(); i++) { + if (laserData.values[i] < obstacle_threshold) { + is_obstacle = true; + return; + } + } + is_obstacle = false; +} + float obstacle_threshold = 0.4; +bool is_obstacle = false; + 100 + + 845.0 + 970.0 + move + interfaces->myMotors->sendV(0.3); +interfaces->myMotors->sendW(0.0); + + + 100 + + 1 + interfaces->calculate_obstacle(); +return interfaces->is_obstacle; + 931.0 + 884.0 + obstacle + 1 + 2 + + + + + 1023.0 + 981.0 + avoid + interfaces->myMotors->sendV(0.0); +interfaces->myMotors->sendW(0.1); + + + 100 + + 1 + interfaces->calculate_obstacle(); +return !interfaces->is_obstacle; + 927.0 + 1056.0 + no obstacle + 2 + 1 + + + + + diff --git a/src/examples/visualStates/jderobot_comm/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml b/src/examples/visualStates/jderobot_comm/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml new file mode 100644 index 000000000..377b82e92 --- /dev/null +++ b/src/examples/visualStates/jderobot_comm/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml @@ -0,0 +1,84 @@ + + + + + + ros + myLaser + /turtlebotROS/laser/scan + + + + Laser + + + ros + myMotors + /turtlebotROS/mobile_base/commands/velocity + + + + Motors + + + + + + 0.0 + 0.0 + root + + def calculate_obstacle(self): + laserData = self.myLaser.getLaserData() + for val in laserData.values: + if (val < self.obstacle_threshold): + self.is_obstacle = True + return + self.is_obstacle = False + self.is_obstacle = False +self.obstacle_threshold = 0.4 + 100 + + 845.0 + 970.0 + move + self.interfaces.myMotors.sendV(0.2) +self.interfaces.myMotors.sendW(0.0) + + + 100 + + 1 + self.interfaces.calculate_obstacle() +return self.interfaces.is_obstacle + 931.0 + 884.0 + obstacle + 1 + 2 + + + + + 1023.0 + 981.0 + avoid + self.interfaces.myMotors.sendV(0.0) +self.interfaces.myMotors.sendW(0.1) + + + 100 + + 1 + self.interfaces.calculate_obstacle() +return not self.interfaces.is_obstacle + 927.0 + 1056.0 + no obstacle + 2 + 1 + + + + + diff --git a/src/examples/visualStates/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml b/src/examples/visualStates/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml new file mode 100644 index 000000000..ba0f58dfc --- /dev/null +++ b/src/examples/visualStates/ros/obstacleAvoidanceCpp/obstacleAvoidanceCpp.xml @@ -0,0 +1,94 @@ + + + + + roscpp + sensor_msgs + geometry_msgs + + + roscpp + sensor_msgs + geometry_msgs + + + + /turtlebotROS/mobile_base/commands/velocity + geometry_msgs/Twist + Publish + + + /turtlebotROS/laser/scan + sensor_msgs/LaserScan + Subscribe + + + + + + 0.0 + 0.0 + root + + void calculate_obstacle() { + sensor_msgs::LaserScan& laserData = getturtlebotROS_laser_scan(); + for (int i = 0; i < laserData.ranges.size(); i++) { + if (laserData.ranges[i] < obstacle_threshold) { + is_obstacle = true; + return; + } + } + is_obstacle = false; +} + float obstacle_threshold = 0.4; +bool is_obstacle = false; + + 100 + + 845.0 + 970.0 + move + geometry_msgs::Twist velCommand; +velCommand.linear.x = 0.3; +velCommand.angular.z = 0.0; +node->publishturtlebotROS_mobile_base_commands_velocity(velCommand); + + + 100 + + 1 + node->calculate_obstacle(); +return node->is_obstacle; + 931.0 + 884.0 + obstacle + 1 + 2 + + + + + 1023.0 + 981.0 + avoid + geometry_msgs::Twist velCommand; +velCommand.linear.x = 0.0; +velCommand.angular.z = 0.1; +node->publishturtlebotROS_mobile_base_commands_velocity(velCommand); + + + 100 + + 1 + node->calculate_obstacle(); +return !node->is_obstacle; + 927.0 + 1056.0 + no obstacle + 2 + 1 + + + + + diff --git a/src/examples/visualStates/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml b/src/examples/visualStates/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml new file mode 100644 index 000000000..5f5a6d73f --- /dev/null +++ b/src/examples/visualStates/ros/obstacleAvoidancePython/obstacleAvoidancePython.xml @@ -0,0 +1,91 @@ + + + + + roscpp + sensor_msgs + geometry_msgs + + + roscpp + sensor_msgs + geometry_msgs + + + + /turtlebotROS/mobile_base/commands/velocity + geometry_msgs/Twist + Publish + + + /turtlebotROS/laser/scan + sensor_msgs/LaserScan + Subscribe + + + + + + 0.0 + 0.0 + root + + def calculate_obstacle(self): + laserData = self.turtlebotROS_laser_scan + for val in laserData.ranges: + if val < self.obstacle_threshold: + self.is_obstacle = True + return + self.is_obstacle = False + self.obstacle_threshold = 0.4 +self.is_obstacle = False + + 100 + + 845.0 + 970.0 + move + velCommand = Twist() +velCommand.linear.x = 0.3 +velCommand.angular.z = 0.0 +self.rosNode.publishturtlebotROS_mobile_base_commands_velocity(velCommand) + + + 100 + + 1 + self.rosNode.calculate_obstacle(); +return self.rosNode.is_obstacle; + 931.0 + 884.0 + obstacle + 1 + 2 + + + + + 1023.0 + 981.0 + avoid + velCommand = Twist() +velCommand.linear.x = 0.0 +velCommand.angular.z = 0.1 +self.rosNode.publishturtlebotROS_mobile_base_commands_velocity(velCommand) + + + 100 + + 1 + self.rosNode.calculate_obstacle() +return not self.rosNode.is_obstacle + 927.0 + 1056.0 + no obstacle + 2 + 1 + + + + +