I was just looking at this the other day. RViz just publishes on certain topics (or calls actionlib actions). Here's some code for setting the initial position of the robot. You can "rostopic echo /initialpose" while setting the initialpose in RViz to see what it looks like.
As others have mentioned, you can also specify an initial pose using parameters in the launch file. Just copy amcl_demo.launch to your development directory and add in the parameters.
To give the robot a goal, just publish a PoseStamped to /move_base_simple/goal or use the actionlib interface to move_base.
python for setting initial pose:
#!/usr/bin/env python
import roslib; roslib.load_manifest('proto')
import rospy
from geometry_msgs.msg import *
def gen_pose():
pub = rospy.Publisher('initialpose', PoseWithCovarianceStamped)
rospy.init_node('initial_pose'); #, log_level=roslib.msg.Log.INFO)
rospy.loginfo("Setting Pose")
p = PoseWithCovarianceStamped();
msg = PoseWithCovariance();
msg.pose = Pose(Point(-0.767, -0.953, 0.000), Quaternion(0.000, 0.000, -0.0149, 0.9999));
msg.covariance = [0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891945200942];
p.pose = msg;
pub.publish(p);
if __name__ == '__main__':
try:
gen_pose()
rospy.loginfo("done")
except Exception, e:
print "error: ", e
Here's some python for setting a movement goal:
... snip ...
location = Pose(Point(15.322, 11.611, 0.000), Quaternion(0.000, 0.000, 0.629, 0.777))
self.goal = MoveBaseGoal()
self.goal.target_pose.pose = location
self.goal.target_pose.header.frame_id = 'map'
self.goal.target_pose.header.stamp = rospy.Time.now()
self.move_base.send_goal(self.goal)
time = self.move_base.wait_for_result(rospy.Duration(300))