41 #include <move_base_msgs/MoveBaseAction.h> 45 #include <boost/thread.hpp> 53 int main(
int argc,
char** argv){
54 ros::init(argc, argv,
"simple_navigation_goals");
58 boost::thread spin_thread = boost::thread(boost::bind(&
spinThread));
65 move_base_msgs::MoveBaseGoal goal;
68 goal.target_pose.header.frame_id =
"base_link";
71 goal.target_pose.pose.position.x = 2.0;
72 goal.target_pose.pose.position.y = 0.2;
81 ROS_INFO(
"Hooray, the base moved 2 meters forward");
83 ROS_INFO(
"The base failed to move forward 2 meters for some reason");
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
SimpleClientGoalState getState() const