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

Fixes for compilation and warnings in Lunar-devel #573

Merged
merged 24 commits into from Apr 28, 2017
Merged
Show file tree
Hide file tree
Changes from 20 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
12 changes: 6 additions & 6 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu.h
Expand Up @@ -75,24 +75,24 @@ namespace gazebo
private: std::string topic_name_;

/// \brief allow specifying constant xyz and rpy offsets
private: math::Pose offset_;
private:ignition::math::Pose3d offset_;

/// \brief A mutex to lock access to fields
/// that are used in message callbacks
private: boost::mutex lock_;

/// \brief save last_time
private: common::Time last_time_;
private: math::Vector3 last_vpos_;
private: math::Vector3 last_veul_;
private: math::Vector3 apos_;
private: math::Vector3 aeul_;
private:ignition::math::Vector3d last_vpos_;
private:ignition::math::Vector3d last_veul_;
private:ignition::math::Vector3d apos_;
private:ignition::math::Vector3d aeul_;

// rate control
private: double update_rate_;

/// \brief: keep initial pose to offset orientation in imu message
private: math::Pose initial_pose_;
private:ignition::math::Pose3d initial_pose_;

/// \brief Gaussian noise
private: double gaussian_noise_;
Expand Down
14 changes: 7 additions & 7 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu_sensor.h
Expand Up @@ -19,8 +19,8 @@

#include <gazebo/common/Plugin.hh>
#include <gazebo/common/UpdateInfo.hh>
#include <gazebo/math/Vector3.hh>
#include <gazebo/math/Pose.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/math/Pose3.hh>
#include <ros/ros.h>
#include <sensor_msgs/Imu.h>
#include <string>
Expand Down Expand Up @@ -79,11 +79,11 @@ namespace gazebo
/// \brief Pointer to the sdf config file.
sdf::ElementPtr sdf;
/// \brief Orientation data from the sensor.
gazebo::math::Quaternion orientation;
ignition::math::Quaterniond orientation;
/// \brief Linear acceleration data from the sensor.
math::Vector3 accelerometer_data;
ignition::math::Vector3d accelerometer_data;
/// \brief Angular velocity data from the sensor.
math::Vector3 gyroscope_data;
ignition::math::Vector3d gyroscope_data;

/// \brief Seed for the Gaussian noise generator.
unsigned int seed;
Expand All @@ -100,8 +100,8 @@ namespace gazebo
/// \brief Gaussian noise.
double gaussian_noise;
/// \brief Offset parameter, position part is unused.
math::Pose offset;
ignition::math::Pose3d offset;
};
}

#endif //GAZEBO_ROS_IMU_SENSOR_H
#endif //GAZEBO_ROS_IMU_SENSOR_H
18 changes: 9 additions & 9 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_p3d.h
Expand Up @@ -89,21 +89,21 @@ namespace gazebo
private: std::string tf_frame_name_;

/// \brief allow specifying constant xyz and rpy offsets
private: math::Pose offset_;
private:ignition::math::Pose3d offset_;

/// \brief mutex to lock access to fields used in message callbacks
private: boost::mutex lock;

/// \brief save last_time
private: common::Time last_time_;
private: math::Vector3 last_vpos_;
private: math::Vector3 last_veul_;
private: math::Vector3 apos_;
private: math::Vector3 aeul_;
private: math::Vector3 last_frame_vpos_;
private: math::Vector3 last_frame_veul_;
private: math::Vector3 frame_apos_;
private: math::Vector3 frame_aeul_;
private:ignition::math::Vector3d last_vpos_;
private:ignition::math::Vector3d last_veul_;
private:ignition::math::Vector3d apos_;
private:ignition::math::Vector3d aeul_;
private:ignition::math::Vector3d last_frame_vpos_;
private:ignition::math::Vector3d last_frame_veul_;
private:ignition::math::Vector3d frame_apos_;
private:ignition::math::Vector3d frame_aeul_;

// rate control
private: double update_rate_;
Expand Down
Expand Up @@ -90,7 +90,7 @@ namespace gazebo {
double rot_;
bool alive_;
common::Time last_odom_publish_time_;
math::Pose last_odom_pose_;
ignition::math::Pose3d last_odom_pose_;

};

Expand Down
16 changes: 8 additions & 8 deletions gazebo_plugins/src/gazebo_ros_block_laser.cpp
Expand Up @@ -82,7 +82,7 @@ void GazeboRosBlockLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
std::string worldName = _parent->WorldName();
this->world_ = physics::get_world(worldName);

last_update_time_ = this->world_->GetSimTime();
last_update_time_ = this->world_->SimTime();

this->node_ = transport::NodePtr(new transport::Node());
this->node_->Init(worldName);
Expand Down Expand Up @@ -236,8 +236,8 @@ void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime)
auto maxAngle = this->parent_ray_sensor_->AngleMax();
auto minAngle = this->parent_ray_sensor_->AngleMin();
#else
math::Angle maxAngle = this->parent_ray_sensor_->GetAngleMax();
math::Angle minAngle = this->parent_ray_sensor_->GetAngleMin();
ignition::math::Angle maxAngle = this->parent_ray_sensor_->PositionMax();
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is wrong I think since GAZEBO_MAJOR_VERSION <6 don't use inition lib, no?

ignition::math::Angle minAngle = this->parent_ray_sensor_->PositionMin();
#endif

double maxRange = this->parent_ray_sensor_->RangeMax();
Expand All @@ -251,8 +251,8 @@ void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime)
auto verticalMaxAngle = this->parent_ray_sensor_->VerticalAngleMax();
auto verticalMinAngle = this->parent_ray_sensor_->VerticalAngleMin();
#else
math::Angle verticalMaxAngle = this->parent_ray_sensor_->GetVerticalAngleMax();
math::Angle verticalMinAngle = this->parent_ray_sensor_->GetVerticalAngleMin();
ignition::math::Angle verticalMaxAngle = this->parent_ray_sensor_->GetVerticalAngleMax();
ignition::math::Angle verticalMinAngle = this->parent_ray_sensor_->GetVerticalAngleMin();
#endif

double yDiff = maxAngle.Radian() - minAngle.Radian();
Expand Down Expand Up @@ -405,9 +405,9 @@ void GazeboRosBlockLaser::OnStats( const boost::shared_ptr<msgs::WorldStatistics
{
this->sim_time_ = msgs::Convert( _msg->sim_time() );

math::Pose pose;
pose.pos.x = 0.5*sin(0.01*this->sim_time_.Double());
gzdbg << "plugin simTime [" << this->sim_time_.Double() << "] update pose [" << pose.pos.x << "]\n";
ignition::math::Pose3d pose;
pose.Pos().X() = 0.5*sin(0.01*this->sim_time_.Double());
gzdbg << "plugin simTime [" << this->sim_time_.Double() << "] update pose [" << pose.Pos().X() << "]\n";
}


Expand Down
80 changes: 40 additions & 40 deletions gazebo_plugins/src/gazebo_ros_bumper.cpp
Expand Up @@ -32,9 +32,9 @@
#include <sdf/Param.hh>
#include <gazebo/common/Exception.hh>
#include <gazebo/sensors/SensorTypes.hh>
#include <gazebo/math/Pose.hh>
#include <gazebo/math/Quaternion.hh>
#include <gazebo/math/Vector3.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>

#include <tf/tf.h>

Expand Down Expand Up @@ -157,7 +157,7 @@ void GazeboRosBumper::OnContact()
*Simulator::Instance()->GetMRMutex());
// look through all models in the world, search for body
// name that matches frameName
phyaics::Model_V all_models = World::Instance()->GetModels();
phyaics::Model_V all_models = World::Instance()->Models();
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

typo even if not used : physics

for (physics::Model_V::iterator iter = all_models.begin();
iter != all_models.end(); iter++)
{
Expand All @@ -177,13 +177,13 @@ void GazeboRosBumper::OnContact()
*/
// get reference frame (body(link)) pose and subtract from it to get
// relative force, torque, position and normal vectors
math::Pose pose, frame_pose;
math::Quaternion rot, frame_rot;
math::Vector3 pos, frame_pos;
ignition::math::Pose3d pose, frame_pose;
ignition::math::Quaterniond rot, frame_rot;
ignition::math::Vector3d pos, frame_pos;
/*
if (myFrame)
{
frame_pose = myFrame->GetWorldPose(); //-this->myBody->GetCoMPose();
frame_pose = myFrame->WorldPose(); //-this->myBody->GetCoMPose();
frame_pos = frame_pose.pos;
frame_rot = frame_pose.rot;
}
Expand All @@ -192,9 +192,9 @@ void GazeboRosBumper::OnContact()
{
// no specific frames specified, use identity pose, keeping
// relative frame at inertial origin
frame_pos = math::Vector3(0, 0, 0);
frame_rot = math::Quaternion(1, 0, 0, 0); // gazebo u,x,y,z == identity
frame_pose = math::Pose(frame_pos, frame_rot);
frame_pos = ignition::math::Vector3d(0, 0, 0);
frame_rot = ignition::math::Quaterniond(1, 0, 0, 0); // gazebo u,x,y,z == identity
frame_pose = ignition::math::Pose3d(frame_pos, frame_rot);
}


Expand Down Expand Up @@ -242,34 +242,34 @@ void GazeboRosBumper::OnContact()
{
// loop through individual contacts between collision1 and collision2
// gzerr << j << " Position:"
// << contact.position(j).x() << " "
// << contact.position(j).y() << " "
// << contact.position(j).z() << "\n";
// << contact.position(j).X()() << " "
// << contact.position(j).Y()() << " "
// << contact.position(j).Z()() << "\n";
// gzerr << " Normal:"
// << contact.normal(j).x() << " "
// << contact.normal(j).y() << " "
// << contact.normal(j).z() << "\n";
// << contact.normal(j).X()() << " "
// << contact.normal(j).Y()() << " "
// << contact.normal(j).Z()() << "\n";
// gzerr << " Depth:" << contact.depth(j) << "\n";

// Get force, torque and rotate into user specified frame.
// frame_rot is identity if world is used (default for now)
math::Vector3 force = frame_rot.RotateVectorReverse(math::Vector3(
contact.wrench(j).body_1_wrench().force().x(),
ignition::math::Vector3d force = frame_rot.RotateVectorReverse(ignition::math::Vector3d(
contact.wrench(j).body_1_wrench().force().x(),
contact.wrench(j).body_1_wrench().force().y(),
contact.wrench(j).body_1_wrench().force().z()));
math::Vector3 torque = frame_rot.RotateVectorReverse(math::Vector3(
ignition::math::Vector3d torque = frame_rot.RotateVectorReverse(ignition::math::Vector3d(
contact.wrench(j).body_1_wrench().torque().x(),
contact.wrench(j).body_1_wrench().torque().y(),
contact.wrench(j).body_1_wrench().torque().z()));

// set wrenches
geometry_msgs::Wrench wrench;
wrench.force.x = force.x;
wrench.force.y = force.y;
wrench.force.z = force.z;
wrench.torque.x = torque.x;
wrench.torque.y = torque.y;
wrench.torque.z = torque.z;
wrench.force.x = force.X();
wrench.force.y = force.Y();
wrench.force.z = force.Z();
wrench.torque.x = torque.X();
wrench.torque.y = torque.Y();
wrench.torque.z = torque.Z();
state.wrenches.push_back(wrench);

total_wrench.force.x += wrench.force.x;
Expand All @@ -281,27 +281,27 @@ void GazeboRosBumper::OnContact()

// transform contact positions into relative frame
// set contact positions
gazebo::math::Vector3 position = frame_rot.RotateVectorReverse(
math::Vector3(contact.position(j).x(),
contact.position(j).y(),
contact.position(j).z()) - frame_pos);
ignition::math::Vector3d position = frame_rot.RotateVectorReverse(
ignition::math::Vector3d(contact.position(j).x(),
contact.position(j).y(),
contact.position(j).z()) - frame_pos);
geometry_msgs::Vector3 contact_position;
contact_position.x = position.x;
contact_position.y = position.y;
contact_position.z = position.z;
contact_position.x = position.X();
contact_position.y = position.Y();
contact_position.z = position.Z();
state.contact_positions.push_back(contact_position);

// rotate normal into user specified frame.
// frame_rot is identity if world is used.
math::Vector3 normal = frame_rot.RotateVectorReverse(
math::Vector3(contact.normal(j).x(),
contact.normal(j).y(),
contact.normal(j).z()));
ignition::math::Vector3d normal = frame_rot.RotateVectorReverse(
ignition::math::Vector3d(contact.normal(j).x(),
contact.normal(j).y(),
contact.normal(j).z()));
// set contact normals
geometry_msgs::Vector3 contact_normal;
contact_normal.x = normal.x;
contact_normal.y = normal.y;
contact_normal.z = normal.z;
contact_normal.x = normal.X();
contact_normal.y = normal.Y();
contact_normal.z = normal.Z();
state.contact_normals.push_back(contact_normal);

// set contact depth, interpenetration
Expand Down
4 changes: 2 additions & 2 deletions gazebo_plugins/src/gazebo_ros_camera_utils.cpp
Expand Up @@ -355,7 +355,7 @@ void GazeboRosCameraUtils::SetHFOV(const std_msgs::Float64::ConstPtr& hfov)
#if GAZEBO_MAJOR_VERSION >= 7
this->camera_->SetHFOV(ignition::math::Angle(hfov->data));
#else
this->camera_->SetHFOV(gazebo::math::Angle(hfov->data));
this->camera_->SetHFOV(ignition::math::Angle(hfov->data));
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this looks also wrong

#endif
}

Expand Down Expand Up @@ -476,7 +476,7 @@ void GazeboRosCameraUtils::Init()
else
{
// check against float precision
if (!gazebo::math::equal(this->focal_length_, computed_focal_length))
if (!ignition::math::equal(this->focal_length_, computed_focal_length))
{
ROS_WARN_NAMED("camera_utils", "The <focal_length>[%f] you have provided for camera_ [%s]"
" is inconsistent with specified image_width [%d] and"
Expand Down