Skip to content

Commit

Permalink
Merge pull request #4 from CPFL/fix-compile-warnings
Browse files Browse the repository at this point in the history
Fix compile warnings
  • Loading branch information
syohex committed Aug 26, 2015
2 parents 6e2c16b + befed7d commit d88f6c0
Show file tree
Hide file tree
Showing 4 changed files with 2 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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.
/////////////////////////////////////////////////////////////////
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<double>::const_iterator it = spline->data.begin(); it != spline->data.end(); ++it)
Expand Down
2 changes: 1 addition & 1 deletion ros/src/data/packages/map_db/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 1 addition & 3 deletions ros/src/data/packages/map_db/lib/map_db/GetFile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,6 @@ GetFile::GetFile(const std::string& host_name, int port)

int GetFile::ConnectHTTP()
{
int r;
unsigned int **addrptr;

#if 0
Expand Down Expand Up @@ -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) {
Expand All @@ -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;
}
Expand Down

0 comments on commit d88f6c0

Please sign in to comment.