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
Changes from 20 commits
Commits
Show all changes
24 commits
Select commit
Hold shift + click to select a range
e06ab08
Replace GetSimTime
j-rivero 9f84ccc
Use ignition::math instead of gazebo::math
j-rivero 3c9acca
Replace GetWorldPose
j-rivero bcc150d
Replace GetLength
j-rivero 53bbf06
Replace GetModels
j-rivero 34e0830
Missing ignition rot method
j-rivero abec013
Missing ignition pos method
j-rivero 68ea054
Replace GetWorldAngularVel
j-rivero 75342aa
Replace GetWorldLinearVel
j-rivero 227d72f
Replace GetWorldLinearVel
j-rivero 24d5ca1
Fix DisconnectWorldUpdateBegin deprecation
j-rivero 0c9657d
Fix DisconnectWorldUpdateBegin deprecation
j-rivero 7c3fe0b
Multiple compiler fixes
j-rivero 958acb7
Multiple compiler fixes
j-rivero 1d2e13b
Multiple compiler fixes
j-rivero 8cd1c13
Multiple compiler fixes
j-rivero c0f2b7b
Multiple compiler fixes
j-rivero 89f6617
Multiple compiler fixes
j-rivero e6f8b34
Multiple compiler fixes
j-rivero c8f0707
Multiple compiler fixes
j-rivero e865a36
Lunar devel initial fix: more fixes ! (#574)
khancyr 6c44c32
Merge with lunar-devel
j-rivero d5086a4
Fix LightByName call
j-rivero 66f3640
Another round of migrating deprecated method
j-rivero File filter
Filter by extension
Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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> | ||
|
||
|
@@ -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(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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++) | ||
{ | ||
|
@@ -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; | ||
} | ||
|
@@ -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); | ||
} | ||
|
||
|
||
|
@@ -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; | ||
|
@@ -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 | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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)); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. this looks also wrong |
||
#endif | ||
} | ||
|
||
|
@@ -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" | ||
|
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
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?