Skip to content
Snippets Groups Projects
Commit 85874180 authored by David Tiede's avatar David Tiede
Browse files

Fix: Not ending movement, pose orientation

parent 229f8eb6
Branches
No related tags found
No related merge requests found
...@@ -32,7 +32,7 @@ void move_toCallback(const std_msgs::String::ConstPtr& msg) ...@@ -32,7 +32,7 @@ void move_toCallback(const std_msgs::String::ConstPtr& msg)
target_pose_2.orientation.x = 0; target_pose_2.orientation.x = 0;
target_pose_2.orientation.y = 0; target_pose_2.orientation.y = 0;
target_pose_2.orientation.z = 0; target_pose_2.orientation.z = 0;
target_pose_2.orientation.w = 0; target_pose_2.orientation.w = 1;
std::vector<geometry_msgs::Pose> waypoints; std::vector<geometry_msgs::Pose> waypoints;
std::string strA ("A"); std::string strA ("A");
...@@ -60,7 +60,7 @@ int main(int argc, char** argv) ...@@ -60,7 +60,7 @@ int main(int argc, char** argv)
{ {
ros::init(argc, argv, "intro_package"); ros::init(argc, argv, "intro_package");
ros::NodeHandle node_handle; ros::NodeHandle node_handle;
ros::AsyncSpinner spinner(1); ros::AsyncSpinner spinner(2);
spinner.start(); spinner.start();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment