2. Some scripts of the turtlebot(python)

本文介绍如何使用 ROS 脚本控制 TurtleBot 前进、避障及前往地图上的特定位置,并展示了如何监测笔记本电脑和 TurtleBot 的电池状态。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

About what?

Analysis the scripts that can control the turtleBot go forward , avoid obstacles and go to a specific location on your map,

monitor the battery status.


TURTLEBOT: roslaunch turtlebot_bringup minimal.launch

then turn to the WORKSTATION

TIPS: all scripts can be downloaded from the website(https://github.com/markwsilliman/turtlebot/)

$git clone https://github.com/markwsilliman/turtlebot/

run scripts: go to the right directory and $python goforward.py


JUST GO FORWARD

# A very basic TurtleBot script that moves TurtleBot forward indefinitely. Press CTRL + C to stop.  To run:

import rospy
from geometry_msgs.msg import Twist

class GoForward():
    def __init__(self):
        # initiliaze
        rospy.init_node('GoForward', anonymous=False)

	# tell user how to stop TurtleBot
	rospy.loginfo("To stop TurtleBot CTRL + C")

        # What function to call when you ctrl + c    
        rospy.on_shutdown(self.shutdown)
        
	# Create a publisher which can "talk" to TurtleBot and tell it to move
        # Tip: You may need to change cmd_vel_mux/input/navi to /cmd_vel if you're not using TurtleBot2
        self.cmd_vel = rospy.Publisher('cmd_vel_mux/input/navi', Twist, queue_size=10)
     
	#TurtleBot will stop if we don't keep telling it to move.  How often should we tell it to move? 10 HZ
        r = rospy.Rate(10);

        # Twist is a datatype for velocity
        move_cmd = Twist()
	# let's go forward at 0.2 m/s
        move_cmd.linear.x = 0.2
	# let's turn at 0 radians/s
	move_cmd.angular.z = 0

	# as long as you haven't ctrl + c keeping doing...
        while not rospy.is_shutdown():
	    # publish the velocity
            self.cmd_vel.publish(move_cmd)
	    # wait for 0.1 seconds (10 HZ) and publish again
            r.sleep()
                        
        
    def shutdown(self):
        # stop turtlebot
        rospy.loginfo("Stop TurtleBot")
	# a default Twist has linear.x of 0 and angular.z of 0.  So it'll stop TurtleBot
        self.cmd_vel.publish(Twist())
	# sleep just makes sure TurtleBot receives the stop command prior to shutting down the script
        rospy.sleep(1)
 
if __name__ == '__main__':
    try:
        GoForward()
    except:
        rospy.loginfo("GoForward node terminated.")<span style="color:#ff0000;">
</span>


GO FORWARD AND AVOID OBSTACLES

TURTLEBOT:  $roslaunch turtlebot_navigation amcl_demo.launch map_file:=/tmp/my_map.yaml

WORKSTATION: $roslaunch turtlebot_rviz_launchers view_navigation.launch --screen

#Code is inspired by http://wiki.ros.org/navigation/Tutorials/SendingSimpleGoals (written in C++).
#TurtleBot must have minimal.launch & amcl_demo.launch running prior to starting this script.

import rospy
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
import actionlib
from actionlib_msgs.msg import *

class GoForwardAvoid():
    def __init__(self):
        rospy.init_node('nav_test', anonymous=False)

	#what to do if shut down (e.g. ctrl + C or failure)
	rospy.on_shutdown(self.shutdown)

	
	#tell the action client that we want to spin a thread by default
	self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
	rospy.loginfo("wait for the action server to come up")
	#allow up to 5 seconds for the action server to come up
	self.move_base.wait_for_server(rospy.Duration(5))

	#we'll send a goal to the robot to move 3 meters forward
	goal = MoveBaseGoal()
	goal.target_pose.header.frame_id = 'base_link'
	goal.target_pose.header.stamp = rospy.Time.now()
	goal.target_pose.pose.position.x = 3.0 #3 meters
	goal.target_pose.pose.orientation.w = 1.0 #go forward

	#start moving
        self.move_base.send_goal(goal)

	#allow TurtleBot up to 60 seconds to complete task
	success = self.move_base.wait_for_result(rospy.Duration(60)) 


	if not success:
                self.move_base.cancel_goal()
                rospy.loginfo("The base failed to move forward 3 meters for some reason")
    	else:
		# We made it!
		state = self.move_base.get_state()
		if state == GoalStatus.SUCCEEDED:
		    rospy.loginfo("Hooray, the base moved 3 meters forward")



    def shutdown(self):
        rospy.loginfo("Stop")


if __name__ == '__main__':
    try:
        GoForwardAvoid()
    except rospy.ROSInterruptException:
        rospy.loginfo("Exception thrown")


GO TO A SPECIFIC LOCATION IN A MAP

TURTLEBOT:  $roslaunch turtlebot_navigation amcl_demo.launch map_file:=/tmp/my_map.yaml

WORKSTATION: $roslaunch turtlebot_rviz_launchers view_navigation.launch --screen

#TurtleBot must have minimal.launch & amcl_demo.launch running prior to starting this script.

import rospy
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
import actionlib
from actionlib_msgs.msg import *
from geometry_msgs.msg import Pose, PoseWithCovarianceStamped, Point, Quaternion, Twist

class GoToPose():
    def __init__(self):
        rospy.init_node('nav_test', anonymous=False)

	#what to do if shut down (e.g. ctrl + C or failure)
	rospy.on_shutdown(self.shutdown)
	
	#tell the action client that we want to spin a thread by default
	self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
	rospy.loginfo("wait for the action server to come up")
	#allow up to 5 seconds for the action server to come up
	self.move_base.wait_for_server(rospy.Duration(5))

	#we'll send a goal to the robot to tell it to move to a pose that's near the docking station
	goal = MoveBaseGoal()
	goal.target_pose.header.frame_id = 'map'
	goal.target_pose.header.stamp = rospy.Time.now()
	#customize the following Point() values so they are appropriate for your location
	goal.target_pose.pose = Pose(Point(2.18, -1.7, 0.000), Quaternion(0.000, 0.000, 0.892, -1.500))

	#start moving
        self.move_base.send_goal(goal)

	#allow TurtleBot up to 60 seconds to complete task
	success = self.move_base.wait_for_result(rospy.Duration(60)) 


	if not success:
                self.move_base.cancel_goal()
                rospy.loginfo("The base failed to reach the desired pose")
    	else:
		# We made it!
		state = self.move_base.get_state()
		if state == GoalStatus.SUCCEEDED:
		    rospy.loginfo("Hooray, reached the desired pose")

    def shutdown(self):
        rospy.loginfo("Stop")


if __name__ == '__main__':
    try:
        GoToPose()
    except rospy.ROSInterruptException:
        rospy.loginfo("Exception thrown")


Monitor the netbook's battery level

import roslib
import rospy
from smart_battery_msgs.msg import SmartBatteryStatus #for netbook battery

class netbook_battery():

	def __init__(self):
		rospy.init_node("netbook_battery")		

		#monitor netbook's battery status.  Everytime anything changes call the call back function self.NetbookPowerEventCallback and pass the data regarding the current battery status
		rospy.Subscriber("/laptop_charge/",SmartBatteryStatus,self.NetbookPowerEventCallback)

		#rospy.spin() tells the program to not exit until you press ctrl + c.  If this wasn't there... it'd subscribe to /laptop_charge/ then immediatly exit (therefore stop "listening" to the thread).
		rospy.spin();


	def NetbookPowerEventCallback(self,data):
		print("Percent: " + str(data.percentage)) 
		print("Charge: " + str(data.charge))
		if(int(data.charge_state) == 1):
			print("Currently charging")
		else:
			print("Not charging")
		print("-----")
		#Tip: try print(data) for a complete list of information available in the /laptop_charge/ thread

if __name__ == '__main__':
	try:
		netbook_battery()
	except rospy.ROSInterruptException:
		rospy.loginfo("exception")

Monitor the kobuki's battery level

import roslib
import rospy
from kobuki_msgs.msg import SensorState

class kobuki_battery():

	kobuki_base_max_charge = 160

	def __init__(self):
		rospy.init_node("kobuki_battery")		

		#monitor Kobuki's power and charging status.  If an event occurs (low battery, charging, not charging etc) call function SensorPowerEventCallback
	        rospy.Subscriber("/mobile_base/sensors/core",SensorState,self.SensorPowerEventCallback)

		#rospy.spin() tells the program to not exit until you press ctrl + c.  If this wasn't there... it'd subscribe and then immediatly exit (therefore stop "listening" to the thread).
		rospy.spin();


	def SensorPowerEventCallback(self,data):
		rospy.loginfo("Kobuki's battery is now: " + str(round(float(data.battery) / float(self.kobuki_base_max_charge) * 100)) + "%")
		if(int(data.charger) == 0) :
			rospy.loginfo("Not charging at docking station")
		else:
			rospy.loginfo("Charging at docking station")
	

if __name__ == '__main__':
	try:
		kobuki_battery()
	except rospy.ROSInterruptException:
		rospy.loginfo("exception")



TIPS: 

1. amcl is a probabilistic localization system for a robot moving in 2D.

url: http://wiki.ros.org/amcl

2.rviz: 3D visualization tool for ROS(debug)

url: http://wiki.ros.org/rviz














评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值