Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fixed shortest angular distance calculation #101

Merged
merged 1 commit into from Feb 20, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 2 additions & 1 deletion cob_linear_nav/CMakeLists.txt
Expand Up @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 2.8.3)
project(cob_linear_nav)

find_package(catkin REQUIRED COMPONENTS
angles
actionlib
cob_srvs
geometry_msgs
Expand Down Expand Up @@ -29,4 +30,4 @@ install(TARGETS cob_linear_nav
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
)
1 change: 1 addition & 0 deletions cob_linear_nav/package.xml
Expand Up @@ -16,6 +16,7 @@

<buildtool_depend>catkin</buildtool_depend>

<depend>angles</depend>
<depend>actionlib</depend>
<depend>cob_srvs</depend>
<depend>geometry_msgs</depend>
Expand Down
4 changes: 2 additions & 2 deletions cob_linear_nav/src/cob_linear_nav.cpp
Expand Up @@ -23,6 +23,7 @@

// ROS includes
#include <ros/ros.h>
#include <angles/angles.h>

#include <pthread.h>

Expand Down Expand Up @@ -407,8 +408,7 @@ double NodeClass::sign(double x) {
}

double NodeClass::getThetaDiffRad(double target, double actual) {
if(fabs(target - actual) <= M_PI) return (target - actual);
else return sign(target - actual) * -2.0f * M_PI - (target - actual);
return angles::shortest_angular_distance(actual, target);
}

void NodeClass::publishVelocitiesGlobal(double vx, double vy, double theta) {
Expand Down