diff --git a/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_trajectory_gen/lattice_trajectory_gen.cpp b/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_trajectory_gen/lattice_trajectory_gen.cpp index ba76095cf7b..4e5cbcd9f42 100644 --- a/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_trajectory_gen/lattice_trajectory_gen.cpp +++ b/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_trajectory_gen/lattice_trajectory_gen.cpp @@ -396,32 +396,6 @@ static void displayNextWaypoint(int i) _vis_pub.publish(marker); } -///////////////////////////////////////////////////////////////// -// obtain the linear/angular velocity toward the next waypoint. -///////////////////////////////////////////////////////////////// -static geometry_msgs::Twist calcTwist(int next_waypoint) -{ - //std::cout << "calculate" << std::endl; - geometry_msgs::Twist twist; - - double radius = _path_pp.calcRadius(next_waypoint); - twist.linear.x = _path_pp.getCmdVelocity(); - - double current_velocity = _current_velocity; - - if (radius > 0 || radius < 0) - { - twist.angular.z = current_velocity / radius; - } - else - { - twist.angular.z = 0; - } - return twist; -} - - - ///////////////////////////////////////////////////////////////// // Safely stop the vehicle. ///////////////////////////////////////////////////////////////// diff --git a/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_twist_convert/lattice_twist_convert.cpp b/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_twist_convert/lattice_twist_convert.cpp index 845c36d96a9..2d1ceb55cc5 100644 --- a/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_twist_convert/lattice_twist_convert.cpp +++ b/ros/src/computing/planning/motion/packages/driving_planner/nodes/lattice_twist_convert/lattice_twist_convert.cpp @@ -209,7 +209,6 @@ void splineCallback(const std_msgs::Float64MultiArray::ConstPtr& spline) } // Reset elapsed time to 0, if called... - double start_time = ros::Time::now().toSec(); int i = 0; for(std::vector::const_iterator it = spline->data.begin(); it != spline->data.end(); ++it) diff --git a/ros/src/data/packages/map_db/CMakeLists.txt b/ros/src/data/packages/map_db/CMakeLists.txt index 392cf10283b..2fc6a8a45b9 100644 --- a/ros/src/data/packages/map_db/CMakeLists.txt +++ b/ros/src/data/packages/map_db/CMakeLists.txt @@ -10,7 +10,7 @@ find_package(catkin REQUIRED COMPONENTS message_generation ) -set(CMAKE_CXX_FLAGS "-std=c++0x -O2 -Wall ${CMAKE_CXX_FLAGS}") +set(CMAKE_CXX_FLAGS "-std=c++0x -O2 -Wall -Wno-unused-result ${CMAKE_CXX_FLAGS}") add_message_files( FILES diff --git a/ros/src/data/packages/map_db/lib/map_db/GetFile.cpp b/ros/src/data/packages/map_db/lib/map_db/GetFile.cpp index 6bd73f5b3c1..fe05731a2b3 100644 --- a/ros/src/data/packages/map_db/lib/map_db/GetFile.cpp +++ b/ros/src/data/packages/map_db/lib/map_db/GetFile.cpp @@ -61,7 +61,6 @@ GetFile::GetFile(const std::string& host_name, int port) int GetFile::ConnectHTTP() { - int r; unsigned int **addrptr; #if 0 @@ -167,7 +166,6 @@ int GetFile::GetHTTPFile(const std::string& value) snprintf(send_buf, sizeof(send_buf), "\r\n"); write(sock, send_buf, strlen(send_buf)); - int r_head = 1; while(1) { n = read(sock, recvdata, sizeof(recvdata)-1); if (n < 0) { @@ -189,7 +187,7 @@ int GetFile::GetHTTPFile(const std::string& value) std::istringstream ss(res); std::string tbuf; - for(int i; i < 10; i++) { + for(int i = 0; i < 10; i++) { std::getline(ss, tbuf); // ignore http header if(tbuf.size() <= 1) break; }