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

Adding MecanumDrive plugin with Odom and Tf, with Tests. #2297

Open
wants to merge 18 commits into
base: gz-sim8
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 15 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
166 changes: 154 additions & 12 deletions src/systems/mecanum_drive/MecanumDrive.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include <vector>

#include <gz/common/Profiler.hh>
#include <gz/math/DiffDriveOdometry.hh>
#include <gz/math/MecanumDriveOdometry.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/SpeedLimiter.hh>
#include <gz/plugin/Register.hh>
Expand Down Expand Up @@ -66,12 +66,19 @@ class gz::sim::systems::MecanumDrivePrivate
/// \param[in] _msg Velocity message
public: void OnCmdVel(const gz::msgs::Twist &_msg);

/// \brief Update odometry and publish an odometry message.
/// \param[in] _info System update information.
/// \param[in] _ecm The EntityComponentManager of the given simulation
/// instance.
public: void UpdateOdometry(const UpdateInfo &_info,
const EntityComponentManager &_ecm);

/// \brief Update the linear and angular velocities.
/// \param[in] _info System update information.
/// \param[in] _ecm The EntityComponentManager of the given simulation
/// instance.
public: void UpdateVelocity(const gz::sim::UpdateInfo &_info,
const gz::sim::EntityComponentManager &_ecm);
public: void UpdateVelocity(const UpdateInfo &_info,
const EntityComponentManager &_ecm);

/// \brief Gazebo communication node.
public: transport::Node node;
Expand Down Expand Up @@ -133,13 +140,13 @@ class gz::sim::systems::MecanumDrivePrivate
/// \brief Last sim time odom was published.
public: std::chrono::steady_clock::duration lastOdomPubTime{0};

/// \brief Diff drive odometry.
public: math::DiffDriveOdometry odom;
/// \brief Mecanum drive odometry.
public: math::MecanumDriveOdometry odom;

/// \brief Diff drive odometry message publisher.
/// \brief Mecanum drive odometry message publisher.
public: transport::Node::Publisher odomPub;

/// \brief Diff drive tf message publisher.
/// \brief Mecanum drive tf message publisher.
public: transport::Node::Publisher tfPub;

/// \brief Linear velocity limiter.
Expand Down Expand Up @@ -280,7 +287,7 @@ void MecanumDrive::Configure(const Entity &_entity,

// Setup odometry.
this->dataPtr->odom.SetWheelParams(this->dataPtr->wheelSeparation,
this->dataPtr->wheelRadius, this->dataPtr->wheelRadius);
this->dataPtr->wheelbase, this->dataPtr->wheelRadius, this->dataPtr->wheelRadius);

// Subscribe to commands
std::vector<std::string> topics;
Expand Down Expand Up @@ -319,13 +326,16 @@ void MecanumDrive::Configure(const Entity &_entity,
if (_sdf->HasElement("child_frame_id"))
this->dataPtr->sdfChildFrameId = _sdf->Get<std::string>("child_frame_id");

gzmsg << "MecanumDrive publishing odom messages on [" << odomTopic << "]"
<< std::endl;

gzmsg << "MecanumDrive subscribing to twist messages on [" << topic << "]"
<< std::endl;
}

//////////////////////////////////////////////////
void MecanumDrive::PreUpdate(const gz::sim::UpdateInfo &_info,
gz::sim::EntityComponentManager &_ecm)
void MecanumDrive::PreUpdate(const UpdateInfo &_info,
EntityComponentManager &_ecm)
{
GZ_PROFILE("MecanumDrive::PreUpdate");

Expand Down Expand Up @@ -450,6 +460,40 @@ void MecanumDrive::PreUpdate(const gz::sim::UpdateInfo &_info,
_ecm.SetComponentData<components::JointVelocityCmd>(joint,
{this->dataPtr->backRightJointSpeed});
}

// Create the joint position components if they don't exist.
auto frontLeftPos = _ecm.Component<components::JointPosition>(
this->dataPtr->frontLeftJoints[0]);
if (!frontLeftPos && _ecm.HasEntity(this->dataPtr->frontLeftJoints[0]))
{
_ecm.CreateComponent(this->dataPtr->frontLeftJoints[0],
components::JointPosition());
}

auto frontRightPos = _ecm.Component<components::JointPosition>(
this->dataPtr->frontRightJoints[0]);
if (!frontRightPos && _ecm.HasEntity(this->dataPtr->frontRightJoints[0]))
{
_ecm.CreateComponent(this->dataPtr->frontRightJoints[0],
components::JointPosition());
}

auto backLeftPos = _ecm.Component<components::JointPosition>(
this->dataPtr->backLeftJoints[0]);
if (!backLeftPos && _ecm.HasEntity(this->dataPtr->backLeftJoints[0]))
{
_ecm.CreateComponent(this->dataPtr->backLeftJoints[0],
components::JointPosition());
}

auto backRightPos = _ecm.Component<components::JointPosition>(
this->dataPtr->backRightJoints[0]);
if (!backRightPos && _ecm.HasEntity(this->dataPtr->backRightJoints[0]))
{
_ecm.CreateComponent(this->dataPtr->backRightJoints[0],
components::JointPosition());
}

}

//////////////////////////////////////////////////
Expand All @@ -462,12 +506,110 @@ void MecanumDrive::PostUpdate(const UpdateInfo &_info,
return;

this->dataPtr->UpdateVelocity(_info, _ecm);
this->dataPtr->UpdateOdometry(_info, _ecm);
}

//////////////////////////////////////////////////
void MecanumDrivePrivate::UpdateOdometry(const UpdateInfo &_info,
const EntityComponentManager &_ecm)
{
GZ_PROFILE("MecanumDrive::UpdateOdometry");
// Initialize, if not already initialized.
if (!this->odom.Initialized())
{
this->odom.Init(std::chrono::steady_clock::time_point(_info.simTime));
return;
}

if (this->frontLeftJoints.empty() || this->frontRightJoints.empty() || this->backLeftJoints.empty() || this->backRightJoints.empty())
muttistefano marked this conversation as resolved.
Show resolved Hide resolved
return;

// Get the first joint positions for each wheel joint.
auto frontLeftPos = _ecm.Component<components::JointPosition>(this->frontLeftJoints[0]);
auto frontRightPos = _ecm.Component<components::JointPosition>(this->frontRightJoints[0]);
auto backLeftPos = _ecm.Component<components::JointPosition>(this->backLeftJoints[0]);
auto backRightPos = _ecm.Component<components::JointPosition>(this->backRightJoints[0]);

// Abort if the joints were not found or just created.
if (!frontLeftPos || !frontRightPos || !backLeftPos || !backRightPos ||
frontLeftPos->Data().empty() || frontRightPos->Data().empty() || backLeftPos->Data().empty() || backRightPos->Data().empty())
{
return;
}

this->odom.Update(frontLeftPos->Data()[0],frontRightPos->Data()[0],backLeftPos->Data()[0],backRightPos->Data()[0],std::chrono::steady_clock::time_point(_info.simTime));
muttistefano marked this conversation as resolved.
Show resolved Hide resolved

// Throttle publishing
auto diff = _info.simTime - this->lastOdomPubTime;
if (diff > std::chrono::steady_clock::duration::zero() &&
diff < this->odomPubPeriod)
{
return;
}
this->lastOdomPubTime = _info.simTime;

// Construct the odometry message and publish it.
msgs::Odometry msg;
msg.mutable_pose()->mutable_position()->set_x(this->odom.X());
msg.mutable_pose()->mutable_position()->set_y(this->odom.Y());

math::Quaterniond orientation(0, 0, *this->odom.Heading());
msgs::Set(msg.mutable_pose()->mutable_orientation(), orientation);

msg.mutable_twist()->mutable_linear()->set_x(this->odom.LinearVelocity());
msg.mutable_twist()->mutable_linear()->set_y(this->odom.LateralVelocity());
msg.mutable_twist()->mutable_angular()->set_z(*this->odom.AngularVelocity());

// Set the time stamp in the header
msg.mutable_header()->mutable_stamp()->CopyFrom(
convert<msgs::Time>(_info.simTime));

// Set the frame id.
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
if (this->sdfFrameId.empty())
{
frame->add_value(this->model.Name(_ecm) + "/odom");
}
else
{
frame->add_value(this->sdfFrameId);
}

std::optional<std::string> linkName = this->canonicalLink.Name(_ecm);
if (this->sdfChildFrameId.empty())
{
if (linkName)
{
auto childFrame = msg.mutable_header()->add_data();
childFrame->set_key("child_frame_id");
childFrame->add_value(this->model.Name(_ecm) + "/" + *linkName);
}
}
else
{
auto childFrame = msg.mutable_header()->add_data();
childFrame->set_key("child_frame_id");
childFrame->add_value(this->sdfChildFrameId);
}

// Construct the Pose_V/tf message and publish it.
msgs::Pose_V tfMsg;
gz::msgs::Pose *tfMsgPose = tfMsg.add_pose();
tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header());
tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position());
tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation());

// Publish the messages
this->odomPub.Publish(msg);
this->tfPub.Publish(tfMsg);

}

//////////////////////////////////////////////////
void MecanumDrivePrivate::UpdateVelocity(
const gz::sim::UpdateInfo &_info,
const gz::sim::EntityComponentManager &/*_ecm*/)
const UpdateInfo &_info,
const EntityComponentManager &/*_ecm*/)
{
GZ_PROFILE("MecanumDrive::UpdateVelocity");

Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ set(tests
logical_audio_sensor_plugin.cc
magnetometer_system.cc
material.cc
mecanum_drive_system.cc
mesh_inertia_calculation.cc
model.cc
model_photo_shoot_default_joints.cc
Expand Down
Loading
Loading