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

Fix compile errors in kobuki_gazebo_plugins with Kinetic and Gazebo7 #45

Closed
wants to merge 6 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions kobuki_gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ project(kobuki_gazebo_plugins)

find_package(gazebo REQUIRED)


find_package(catkin REQUIRED COMPONENTS gazebo_ros
gazebo_plugins
geometry_msgs
Expand All @@ -25,6 +26,8 @@ catkin_package(INCLUDE_DIRS include
std_msgs
tf)

set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} " -std=c++11")

link_directories(${GAZEBO_LIBRARY_DIRS})
include_directories(include
${catkin_INCLUDE_DIRS}
Expand Down
10 changes: 5 additions & 5 deletions kobuki_gazebo_plugins/src/gazebo_ros_kobuki_loads.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,11 +212,11 @@ bool GazeboRosKobuki::prepareCliffSensor()
<< " Did you specify it?" << " [" << node_name_ <<"]");
return false;
}
cliff_sensor_left_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
cliff_sensor_left_ = std::dynamic_pointer_cast<sensors::RaySensor>(
sensors::SensorManager::Instance()->GetSensor(cliff_sensor_left_name));
cliff_sensor_center_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
cliff_sensor_center_ = std::dynamic_pointer_cast<sensors::RaySensor>(
sensors::SensorManager::Instance()->GetSensor(cliff_sensor_center_name));
cliff_sensor_right_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
cliff_sensor_right_ = std::dynamic_pointer_cast<sensors::RaySensor>(
sensors::SensorManager::Instance()->GetSensor(cliff_sensor_right_name));
if (!cliff_sensor_left_)
{
Expand Down Expand Up @@ -267,7 +267,7 @@ bool GazeboRosKobuki::prepareBumper()
<< " Did you specify it?" << " [" << node_name_ <<"]");
return false;
}
bumper_ = boost::dynamic_pointer_cast<sensors::ContactSensor>(
bumper_ = std::dynamic_pointer_cast<sensors::ContactSensor>(
sensors::SensorManager::Instance()->GetSensor(bumper_name));
if (!bumper_)
{
Expand All @@ -294,7 +294,7 @@ bool GazeboRosKobuki::prepareIMU()
<< " Did you specify it?" << " [" << node_name_ <<"]");
return false;
}
imu_ = boost::dynamic_pointer_cast<sensors::ImuSensor>(
imu_ = std::dynamic_pointer_cast<sensors::ImuSensor>(
sensors::get_sensor(world_->GetName()+"::"+node_name_+"::base_footprint::"+imu_name));
if (!imu_)
{
Expand Down
12 changes: 5 additions & 7 deletions kobuki_gazebo_plugins/src/gazebo_ros_kobuki_updates.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,13 +73,13 @@ void GazeboRosKobuki::updateOdometry(common::Time& step_time)
d1 = step_time.Double() * (wheel_diam_ / 2) * joints_[LEFT]->GetVelocity(0);
d2 = step_time.Double() * (wheel_diam_ / 2) * joints_[RIGHT]->GetVelocity(0);
// Can see NaN values here, just zero them out if needed
if (isnan(d1))
if (std::isnan(d1))
{
ROS_WARN_STREAM_THROTTLE(0.1, "Gazebo ROS Kobuki plugin: NaN in d1. Step time: " << step_time.Double()
<< ", WD: " << wheel_diam_ << ", velocity: " << joints_[LEFT]->GetVelocity(0));
d1 = 0;
}
if (isnan(d2))
if (std::isnan(d2))
{
ROS_WARN_STREAM_THROTTLE(0.1, "Gazebo ROS Kobuki plugin: NaN in d2. Step time: " << step_time.Double()
<< ", WD: " << wheel_diam_ << ", velocity: " << joints_[RIGHT]->GetVelocity(0));
Expand All @@ -89,7 +89,7 @@ void GazeboRosKobuki::updateOdometry(common::Time& step_time)
da = (d2 - d1) / wheel_sep_; // ignored

// Just as in the Kobuki driver, the angular velocity is taken directly from the IMU
vel_angular_ = imu_->GetAngularVelocity();
vel_angular_ = imu_->AngularVelocity();

// Compute odometric pose
odom_pose_[0] += dr * cos( odom_pose_[2] );
Expand Down Expand Up @@ -144,7 +144,7 @@ void GazeboRosKobuki::updateOdometry(common::Time& step_time)
void GazeboRosKobuki::updateIMU()
{
imu_msg_.header = joint_state_.header;
math::Quaternion quat = imu_->GetOrientation();
math::Quaternion quat = imu_->Orientation();
imu_msg_.orientation.x = quat.x;
imu_msg_.orientation.y = quat.y;
imu_msg_.orientation.z = quat.z;
Expand All @@ -158,7 +158,7 @@ void GazeboRosKobuki::updateIMU()
imu_msg_.angular_velocity_covariance[0] = 1e6;
imu_msg_.angular_velocity_covariance[4] = 1e6;
imu_msg_.angular_velocity_covariance[8] = 0.05;
math::Vector3 lin_acc = imu_->GetLinearAcceleration();
math::Vector3 lin_acc = imu_->LinearAcceleration();
imu_msg_.linear_acceleration.x = lin_acc.x;
imu_msg_.linear_acceleration.y = lin_acc.y;
imu_msg_.linear_acceleration.z = lin_acc.z;
Expand All @@ -178,8 +178,6 @@ void GazeboRosKobuki::propagateVelocityCommands()
}
joints_[LEFT]->SetVelocity(0, wheel_speed_cmd_[LEFT] / (wheel_diam_ / 2.0));
joints_[RIGHT]->SetVelocity(0, wheel_speed_cmd_[RIGHT] / (wheel_diam_ / 2.0));
joints_[LEFT]->SetMaxForce(0, torque_);
joints_[RIGHT]->SetMaxForce(0, torque_);
}

/*
Expand Down