From cd579a7e7c893247ac3340b50e70119fe6c299dc Mon Sep 17 00:00:00 2001 From: hotic06 <40561364+hotic06@users.noreply.github.com> Date: Wed, 12 Feb 2020 22:55:23 +0900 Subject: [PATCH 1/6] Update burger_navigation.rviz --- burger_navigation/rviz/burger_navigation.rviz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/burger_navigation/rviz/burger_navigation.rviz b/burger_navigation/rviz/burger_navigation.rviz index fcace02b..320eed3d 100644 --- a/burger_navigation/rviz/burger_navigation.rviz +++ b/burger_navigation/rviz/burger_navigation.rviz @@ -291,7 +291,7 @@ Visualization Manager: Draw Behind: false Enabled: true Name: Costmap - Topic: /red_bot/move_base/local_costmap/costmap + Topic: /move_base/local_costmap/costmap Unreliable: false Use Timestamp: false Value: true From b95d0c7e3b69bae1d8b83040fe858af76e1b183a Mon Sep 17 00:00:00 2001 From: dashimaki360 <17.punch@gmail.com> Date: Sun, 16 Feb 2020 17:57:47 +0900 Subject: [PATCH 2/6] add level 1 enemy cheese burger --- burger_war/launch/sim_level_1_cheese.launch | 15 +++ burger_war/scripts/level_1_cheese.py | 105 ++++++++++++++++++++ 2 files changed, 120 insertions(+) create mode 100644 burger_war/launch/sim_level_1_cheese.launch create mode 100755 burger_war/scripts/level_1_cheese.py diff --git a/burger_war/launch/sim_level_1_cheese.launch b/burger_war/launch/sim_level_1_cheese.launch new file mode 100644 index 00000000..e60181e2 --- /dev/null +++ b/burger_war/launch/sim_level_1_cheese.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/burger_war/scripts/level_1_cheese.py b/burger_war/scripts/level_1_cheese.py new file mode 100755 index 00000000..2c5f15c8 --- /dev/null +++ b/burger_war/scripts/level_1_cheese.py @@ -0,0 +1,105 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +# level_1_cheese.py +# write by yamaguchi takuya @dashimaki360 +## GO and Back only + + +import rospy +import random + +from geometry_msgs.msg import Twist +from nav_msgs.msg import Odometry +from sensor_msgs.msg import JointState + +class CheeseBurger(): + def __init__(self, bot_name): + # bot name + self.name = bot_name + # robot state 'go' or 'back' + self.state = 'back' + # robot wheel rot + self.wheel_rot_r = 0 + self.wheel_rot_l = 0 + self.pose_x = 0 + self.pose_y = 0 + + # speed [m/s] + self.speed = 0.25 + + # publisher + self.vel_pub = rospy.Publisher('cmd_vel', Twist,queue_size=1) + # subscriber + self.odom_sub = rospy.Subscriber('odom', Odometry, self.odomCallback) + self.odom_sub = rospy.Subscriber('joint_states', JointState, self.jointstateCallback) + + def odomCallback(self, data): + ''' + Dont use odom in this program now + update robot pose in gazebo + ''' + self.pose_x = data.pose.pose.position.x + self.pose_y = data.pose.pose.position.y + + def jointstateCallback(self, data): + ''' + update wheel rotation num + ''' + self.wheel_rot_r = data.position[0] + self.wheel_rot_l = data.position[1] + + def calcTwist(self): + ''' + calc twist from self.state + 'go' -> self.speed, 'back' -> -self.speed + ''' + if self.state == 'go': + # set speed x axis + x = self.speed + elif self.state == 'back': + # set speed x axis + x = -1 * self.speed + else: + # error state + x = 0 + rospy.logerr("SioBot state is invalid value %s", self.state) + + twist = Twist() + twist.linear.x = x; twist.linear.y = 0; twist.linear.z = 0 + twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0 + return twist + + def calcState(self): + ''' + update robot state 'go' or 'back' + ''' + if self.state == 'go' and self.wheel_rot_r > 30: + self.state = 'back' + elif self.state == 'back' and self.wheel_rot_r < 5: + self.state = 'go' + + def strategy(self): + ''' + calc Twist and publish cmd_vel topic + Go and Back loop forever + ''' + r = rospy.Rate(5) # change speed 1fps + + while not rospy.is_shutdown(): + # update state from now state and wheel rotation + self.calcState() + # update twist + twist = self.calcTwist() + + # publish twist topic + self.vel_pub.publish(twist) + + r.sleep() + + +if __name__ == '__main__': + rospy.init_node('enemy') + bot = CheeseBurger('cheese_burger') + bot.strategy() + From b5d6c4744cb18c2c3e197d9b19bcbcc7aa06b121 Mon Sep 17 00:00:00 2001 From: dashimaki360 <17.punch@gmail.com> Date: Sun, 16 Feb 2020 19:05:45 +0900 Subject: [PATCH 3/6] add level 2 teriyaki burger. not finished. --- ...im_level_2_teriyaki_burger_navigation.rviz | 235 ++++++++++++++++++ burger_war/launch/sim_level_2_teriyaki.launch | 85 +++++++ burger_war/scripts/level_2_teriyaki.py | 105 ++++++++ 3 files changed, 425 insertions(+) create mode 100644 burger_navigation/rviz/sim_level_2_teriyaki_burger_navigation.rviz create mode 100644 burger_war/launch/sim_level_2_teriyaki.launch create mode 100755 burger_war/scripts/level_2_teriyaki.py diff --git a/burger_navigation/rviz/sim_level_2_teriyaki_burger_navigation.rviz b/burger_navigation/rviz/sim_level_2_teriyaki_burger_navigation.rviz new file mode 100644 index 00000000..61ed261b --- /dev/null +++ b/burger_navigation/rviz/sim_level_2_teriyaki_burger_navigation.rviz @@ -0,0 +1,235 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1/Status1 + - /TF1 + - /TF1/Status1 + - /TF1/Frames1 + - /TF1/Tree1 + - /LaserScan1 + - /LaserScan1/Status1 + - /Map1 + - /Amcl Particles1 + Splitter Ratio: 0.5 + Tree Height: 843 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + Name: Tool Properties + Splitter Ratio: 0.588679016 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 20 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: false + Visual Enabled: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: false + base_footprint: + Value: true + enemy_bot/base_footprint: + Value: true + enemy_bot/base_link: + Value: true + enemy_bot/base_scan: + Value: true + enemy_bot/caster_back_link: + Value: true + enemy_bot/imu_link: + Value: true + enemy_bot/map: + Value: true + enemy_bot/odom: + Value: true + enemy_bot/wheel_left_link: + Value: true + enemy_bot/wheel_right_link: + Value: true + odom: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + enemy_bot/map: + enemy_bot/odom: + enemy_bot/base_footprint: + enemy_bot/base_link: + enemy_bot/base_scan: + {} + enemy_bot/caster_back_link: + {} + enemy_bot/imu_link: + {} + enemy_bot/wheel_left_link: + {} + enemy_bot/wheel_right_link: + {} + Update Interval: 0 + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 13069 + Min Color: 0; 0; 0 + Min Intensity: 28 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.0300000012 + Style: Flat Squares + Topic: /enemy_bot/scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.5 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /enemy_bot/map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Arrow Length: 0.0500000007 + Axes Length: 0.300000012 + Axes Radius: 0.00999999978 + Class: rviz/PoseArray + Color: 0; 192; 0 + Enabled: true + Head Length: 0.0700000003 + Head Radius: 0.0299999993 + Name: Amcl Particles + Shaft Length: 0.230000004 + Shaft Radius: 0.00999999978 + Shape: Arrow (Flat) + Topic: /enemy_bot/particlecloud + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: enemy_bot/map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/MoveCamera + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/Select + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/Measure + Value: true + Views: + Current: + Angle: -9.5958004 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Scale: 136.429901 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1056 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001e9000003dafc0200000007fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000003da000000dd00fffffffb0000000a0049006d0061006700650000000319000000cc0000000000000000fb0000000a0049006d0061006700650000000330000000ce0000000000000000000000010000010f000003dafc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000003da000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000030000fffffffb0000000800540069006d0065010000000000000450000000000000000000000550000003da00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1855 + X: 1985 + Y: 24 diff --git a/burger_war/launch/sim_level_2_teriyaki.launch b/burger_war/launch/sim_level_2_teriyaki.launch new file mode 100644 index 00000000..36820eaa --- /dev/null +++ b/burger_war/launch/sim_level_2_teriyaki.launch @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/burger_war/scripts/level_2_teriyaki.py b/burger_war/scripts/level_2_teriyaki.py new file mode 100755 index 00000000..2c5f15c8 --- /dev/null +++ b/burger_war/scripts/level_2_teriyaki.py @@ -0,0 +1,105 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +# level_1_cheese.py +# write by yamaguchi takuya @dashimaki360 +## GO and Back only + + +import rospy +import random + +from geometry_msgs.msg import Twist +from nav_msgs.msg import Odometry +from sensor_msgs.msg import JointState + +class CheeseBurger(): + def __init__(self, bot_name): + # bot name + self.name = bot_name + # robot state 'go' or 'back' + self.state = 'back' + # robot wheel rot + self.wheel_rot_r = 0 + self.wheel_rot_l = 0 + self.pose_x = 0 + self.pose_y = 0 + + # speed [m/s] + self.speed = 0.25 + + # publisher + self.vel_pub = rospy.Publisher('cmd_vel', Twist,queue_size=1) + # subscriber + self.odom_sub = rospy.Subscriber('odom', Odometry, self.odomCallback) + self.odom_sub = rospy.Subscriber('joint_states', JointState, self.jointstateCallback) + + def odomCallback(self, data): + ''' + Dont use odom in this program now + update robot pose in gazebo + ''' + self.pose_x = data.pose.pose.position.x + self.pose_y = data.pose.pose.position.y + + def jointstateCallback(self, data): + ''' + update wheel rotation num + ''' + self.wheel_rot_r = data.position[0] + self.wheel_rot_l = data.position[1] + + def calcTwist(self): + ''' + calc twist from self.state + 'go' -> self.speed, 'back' -> -self.speed + ''' + if self.state == 'go': + # set speed x axis + x = self.speed + elif self.state == 'back': + # set speed x axis + x = -1 * self.speed + else: + # error state + x = 0 + rospy.logerr("SioBot state is invalid value %s", self.state) + + twist = Twist() + twist.linear.x = x; twist.linear.y = 0; twist.linear.z = 0 + twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0 + return twist + + def calcState(self): + ''' + update robot state 'go' or 'back' + ''' + if self.state == 'go' and self.wheel_rot_r > 30: + self.state = 'back' + elif self.state == 'back' and self.wheel_rot_r < 5: + self.state = 'go' + + def strategy(self): + ''' + calc Twist and publish cmd_vel topic + Go and Back loop forever + ''' + r = rospy.Rate(5) # change speed 1fps + + while not rospy.is_shutdown(): + # update state from now state and wheel rotation + self.calcState() + # update twist + twist = self.calcTwist() + + # publish twist topic + self.vel_pub.publish(twist) + + r.sleep() + + +if __name__ == '__main__': + rospy.init_node('enemy') + bot = CheeseBurger('cheese_burger') + bot.strategy() + From 51b58a820ea40adccaadb9044f263f3aadd9198a Mon Sep 17 00:00:00 2001 From: dashimaki360 <17.punch@gmail.com> Date: Sun, 16 Feb 2020 23:52:30 +0900 Subject: [PATCH 4/6] update level 2 teriyaki. yet not finished. --- burger_war/launch/sim_level_2_teriyaki.launch | 11 +- burger_war/scripts/level_2_teriyaki.py | 146 +++++++++++------- 2 files changed, 95 insertions(+), 62 deletions(-) diff --git a/burger_war/launch/sim_level_2_teriyaki.launch b/burger_war/launch/sim_level_2_teriyaki.launch index 36820eaa..33c3f5ad 100644 --- a/burger_war/launch/sim_level_2_teriyaki.launch +++ b/burger_war/launch/sim_level_2_teriyaki.launch @@ -2,6 +2,7 @@ + @@ -10,7 +11,7 @@ - + @@ -60,10 +61,10 @@ - - - - + + + + diff --git a/burger_war/scripts/level_2_teriyaki.py b/burger_war/scripts/level_2_teriyaki.py index 2c5f15c8..bd70d0d3 100755 --- a/burger_war/scripts/level_2_teriyaki.py +++ b/burger_war/scripts/level_2_teriyaki.py @@ -1,105 +1,137 @@ #!/usr/bin/env python # -*- coding: utf-8 -*- -# level_1_cheese.py +# level_2_teriyaki.py # write by yamaguchi takuya @dashimaki360 -## GO and Back only +## GO around field by AMCL localizer import rospy import random from geometry_msgs.msg import Twist -from nav_msgs.msg import Odometry -from sensor_msgs.msg import JointState - -class CheeseBurger(): +from geometry_msgs.msg import PoseWithCovarianceStamped +from sensor_msgs.msg import LaserScan + +import tf + +PI = 3.1416 +# 8x8 [rad] +TARGET_TH = ( + (-PI/4, -PI/4, -PI/2, -PI/2, -PI*3/4, -PI*3/4, -PI*3/4, -PI*3/4), + (-PI/4, -PI/4, -PI/4, -PI/4, -PI*3/4, -PI*3/4, -PI*3/4, -PI*3/4), + (-PI/4, -PI/4, -PI/4, 0, -PI/2, -PI*3/4, -PI*3/4, PI), + (-PI/4, -PI/4, 0, 0, -PI/2, -PI/2, -PI*3/4, PI), + ( 0, PI/4, PI/2, PI/2, PI, PI, PI*3/4, PI*3/4), + ( 0, PI/4, PI/3, PI/2, PI, PI*3/4, PI*3/4, PI*3/4), + ( PI/4, PI/4, PI/3, PI/4, PI*3/4, PI*3/4, PI*3/4, PI*3/4), + ( PI/4, PI/4, PI/4, PI/4, PI/2, PI/2, PI*3/4, PI*3/4), +) +WIDTH = 1.2 * (2 **0.5) # [m] + +class TeriyakiBurger(): def __init__(self, bot_name): # bot name self.name = bot_name - # robot state 'go' or 'back' - self.state = 'back' + # robot state 'inner' or 'outer' + self.state = 'inner' # robot wheel rot self.wheel_rot_r = 0 self.wheel_rot_l = 0 self.pose_x = 0 self.pose_y = 0 + self.k = 0.5 + # speed [m/s] - self.speed = 0.25 + self.speed = 0.07 # publisher self.vel_pub = rospy.Publisher('cmd_vel', Twist,queue_size=1) # subscriber - self.odom_sub = rospy.Subscriber('odom', Odometry, self.odomCallback) - self.odom_sub = rospy.Subscriber('joint_states', JointState, self.jointstateCallback) + self.pose_sub = rospy.Subscriber('amcl_pose', PoseWithCovarianceStamped, self.poseCallback) + self.lidar_sub = rospy.Subscriber('scan', LaserScan, self.lidarCallback) - def odomCallback(self, data): - ''' - Dont use odom in this program now - update robot pose in gazebo - ''' - self.pose_x = data.pose.pose.position.x - self.pose_y = data.pose.pose.position.y + self.twist = Twist() + self.twist.linear.x = self.speed; self.twist.linear.y = 0.; self.twist.linear.z = 0. + self.twist.angular.x = 0.; self.twist.angular.y = 0.; self.twist.angular.z = 0. + - def jointstateCallback(self, data): - ''' - update wheel rotation num - ''' - self.wheel_rot_r = data.position[0] - self.wheel_rot_l = data.position[1] - def calcTwist(self): + def poseCallback(self, data): ''' - calc twist from self.state - 'go' -> self.speed, 'back' -> -self.speed + pose topic from amcl localizer + update robot twist ''' - if self.state == 'go': - # set speed x axis - x = self.speed - elif self.state == 'back': - # set speed x axis - x = -1 * self.speed - else: - # error state - x = 0 - rospy.logerr("SioBot state is invalid value %s", self.state) - - twist = Twist() - twist.linear.x = x; twist.linear.y = 0; twist.linear.z = 0 - twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0 - return twist - - def calcState(self): + pose_x = data.pose.pose.position.x + pose_y = data.pose.pose.position.y + quaternion = data.pose.pose.orientation + rpy = tf.transformations.euler_from_quaternion((quaternion.x, quaternion.y, quaternion.z, quaternion.w)) + th = rpy[2] + + th_xy = self.calcTargetTheta(pose_x,pose_y) + + th_diff = th_xy - th + while not PI >= th_diff >= -PI: + if th_diff > 0: + th_diff -= 2*PI + elif th_diff < 0: + th_diff += 2*PI + new_twist_ang_z = th_diff * self.k + + self.twist.angular.z = new_twist_ang_z + print(pose_x, pose_y, th, th_xy, new_twist_ang_z) + + + def calcTargetTheta(self, pose_x, pose_y): + x = self.poseToindex(pose_x) + y = self.poseToindex(pose_y) + th = TARGET_TH[x][y] + print("POSE pose_x: {}, pose_y: {}. INDEX x:{}, y:{}".format(pose_x, pose_y, x, y)) + return th + + def poseToindex(self, pose): + i = 7 - int((pose + WIDTH) / (2 * WIDTH) * 8) + i = max(0, min(7, i)) + return i + + def lidarCallback(self, data): ''' - update robot state 'go' or 'back' + lidar scan use for bumper + controll speed.x ''' - if self.state == 'go' and self.wheel_rot_r > 30: - self.state = 'back' - elif self.state == 'back' and self.wheel_rot_r < 5: - self.state = 'go' + is_near_wall = self.isNearWall(data.ranges) + if is_near_wall: + self.twist.linear.x = -self.speed + else: + self.twist.linear.x = self.speed + + def isNearWall(self, scan): + if not len(scan) == 360: + return False + forword_scan = scan[:10] + scan[-10:] + # drop too small value ex) 0.0 + forword_scan = [x for x in forword_scan if x > 0.1] + if min(forword_scan) < 0.2: + return True + return False def strategy(self): ''' calc Twist and publish cmd_vel topic Go and Back loop forever ''' - r = rospy.Rate(5) # change speed 1fps + r = rospy.Rate(10) # change speed 10fps while not rospy.is_shutdown(): - # update state from now state and wheel rotation - self.calcState() - # update twist - twist = self.calcTwist() - # publish twist topic - self.vel_pub.publish(twist) + self.vel_pub.publish(self.twist) r.sleep() if __name__ == '__main__': rospy.init_node('enemy') - bot = CheeseBurger('cheese_burger') + bot = TeriyakiBurger('teriyaki_burger') bot.strategy() From de1d660e70c864ec7b05a6161676f4b9588c3052 Mon Sep 17 00:00:00 2001 From: dashimaki360 <17.punch@gmail.com> Date: Tue, 18 Feb 2020 11:34:11 +0900 Subject: [PATCH 5/6] add C++ example. randomRun --- burger_war/CMakeLists.txt | 11 +++++ burger_war/src/randomRun.cpp | 83 ++++++++++++++++++++++++++++++++++++ 2 files changed, 94 insertions(+) create mode 100644 burger_war/src/randomRun.cpp diff --git a/burger_war/CMakeLists.txt b/burger_war/CMakeLists.txt index 7e56e7ed..f36baef1 100644 --- a/burger_war/CMakeLists.txt +++ b/burger_war/CMakeLists.txt @@ -11,6 +11,12 @@ find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs + geometry_msgs + control_msgs + std_msgs + sensor_msgs + cv_bridge + tf ) ## System dependencies are found with CMake's conventions @@ -135,6 +141,7 @@ include_directories( ## The recommended prefix ensures that target names across packages don't collide # add_executable(${PROJECT_NAME}_node src/burger_war_node.cpp) + ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the ## target back to the shorter version for ease of user use @@ -197,3 +204,7 @@ include_directories( ## Add folders to be run by python nosetests # catkin_add_nosetests(test) + + +add_executable(randomRun src/randomRun.cpp) +target_link_libraries(randomRun ${catkin_LIBRARIES}) \ No newline at end of file diff --git a/burger_war/src/randomRun.cpp b/burger_war/src/randomRun.cpp new file mode 100644 index 00000000..8160b9e2 --- /dev/null +++ b/burger_war/src/randomRun.cpp @@ -0,0 +1,83 @@ +// burger war c++ example +// respect from https://demura.net/lecture/13932.html + + +#include "ros/ros.h" // rosで必要はヘッダーファイル +#include // ロボットを動かすために必要 +#include +using namespace std; + + + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "my_teleop_node"); + // initでROSを初期化し、my_teleop_nodeという名前をノードにつける + // 同じ名前のノードが複数あるとだめなので、ユニークな名前をつける + + ros::NodeHandle nh; + // ノードハンドラの作成。ハンドラは必要時に起動される。 + + ros::Publisher pub; + // パブリッシャの作成。トピックに対してデータを送信。 + + ros::Rate rate(1); + // ループの頻度を設定するためのオブジェクトを作成。この場合は1Hz、1秒間に1回 + + geometry_msgs::Twist vel; + // geometry_msgs::Twist この型は並進速度と回転速度(vector3:3次元ベクトル) を合わせたもので、速度指令によく使われる + + pub= nh.advertise("cmd_vel", 10); + // マスターにgeometry_msgs::Twist型のデータを送ることを伝える + // マスターは/cmd_velトピック(1番目の引数)を購読する + // 全てのノードにトピックができたことを知らせる(advertise)。 + // 2番目の引数はデータのバッファサイズ + + + int rnd = 0; + float x = 0.0; + float th = 0.0; + + while (ros::ok()) { // このノードが使える間は無限ループする + + rnd = rand() % 1000; + + if (rnd < 250){ + x = 0.2; + th = 0.0; + } + else if (rnd < 500){ + x = -0.2; + th = 0.0; + } + else if (rnd < 750){ + x = 0.0; + th = 1.0; + } + else if (rnd < 1000){ + x = 0.0; + th = -1.0; + } + else { + x = 0.0; + th = 0.0; + } + + // linear.xは前後方向の並進速度(m/s)。前方向が正。 + // angular.zは回転速度(rad/s)。反時計回りが正。 + vel.linear.x = x; + vel.linear.y = 0.0; + vel.linear.z = 0.0; + vel.angular.x = 0.0; + vel.angular.y = 0.0; + vel.angular.z = th; + + pub.publish(vel); // 速度指令メッセージをパブリッシュ(送信) + cout << vel << endl; + ros::spinOnce(); // 1回だけコールバック関数を呼び出す + rate.sleep(); // 指定した周期でループするよう寝て待つ + } + + return 0; +} + From 5668c8c20e32f17ed1966947e96c9bc0cc1406b9 Mon Sep 17 00:00:00 2001 From: Takuya Yamaguchi <17.punch@gmail.com> Date: Tue, 18 Feb 2020 17:37:21 +0900 Subject: [PATCH 6/6] Update README.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit GAZEBO モデルパスの設定を .bashrc に追加するように変更 Turtlebot3のモデル名の指定を環境変数に追加。 --- README.md | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 6d991496..6e3503a0 100644 --- a/README.md +++ b/README.md @@ -57,11 +57,15 @@ cd ~/catkin_ws/src git clone https://github.com/OneNightROBOCON/burger_war ``` -このリポジトリのフィールド用のGAZEBOモデルにPATHを通す +このリポジトリのフィールド用のGAZEBOモデルにPATHを通す。 + +Turtlebot3のモデル名の指定を環境変数に追加。 ``` -export GAZEBO_MODEL_PATH=$HOME/catkin_ws/src/burger_war/burger_war/models/ +echo "export GAZEBO_MODEL_PATH=$HOME/catkin_ws/src/burger_war/burger_war/models/" >> ~/.bashrc +echo "export TURTLEBOT3_MODEL=burger" >> ~/.bashrc +source ~/.bashrc ``` -シェルごとに毎回実行するのは面倒なので上記は`~/.bashrc`に書いておくと便利です。 + ### 3. 依存ライブラリのインストール - pip : pythonのパッケージ管理ツール