mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
Bring back the gazebo plugins (#1063)
The models and meshes are not included. We will need to find an alternate way to reintegrate these and use them. * Add simulation/gz_msgs back, and build with Gradle. * Add back in the frc simulation plugins for gazebo. * Add a new shared library, halsim_gazebo. This library will become the interface between the HAL sim layer and gazebo. * Preserve the first channel number used in created Encoders in the Sim MockData. This allows us to use the DIO channel number to connect with simulated encoders. * Have the HAL Simulator set the reverse direction on creation. This enables a simulator to be aware of the direction. * Add a drive_motor plugin. This is a bit of a 'magic' motor, which allows us to build robot models that drive in a more realistic fashion. It does this by apply forces directly to the chassis, rather than relying on the complex motion dynamics of a driven wheel. This in turn allows the model to reduce wheel friction, reducing scrub, and allowing for a more natural driving experience.
This commit is contained in:
committed by
Peter Johnson
parent
70960b0251
commit
ebd41fe0bb
102
simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp
Normal file
102
simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp
Normal file
@@ -0,0 +1,102 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "encoder.h"
|
||||
|
||||
#include <boost/algorithm/string/replace.hpp>
|
||||
|
||||
GZ_REGISTER_MODEL_PLUGIN(Encoder)
|
||||
|
||||
void Encoder::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
|
||||
this->model = model;
|
||||
|
||||
// Parse SDF properties
|
||||
joint = model->GetJoint(sdf->Get<std::string>("joint"));
|
||||
if (sdf->HasElement("topic")) {
|
||||
topic = sdf->Get<std::string>("topic");
|
||||
} else {
|
||||
topic = "~/" + sdf->GetAttribute("name")->GetAsString();
|
||||
}
|
||||
|
||||
if (sdf->HasElement("units")) {
|
||||
radians = sdf->Get<std::string>("units") != "degrees";
|
||||
} else {
|
||||
radians = true;
|
||||
}
|
||||
multiplier = 1.0;
|
||||
zero = GetAngle();
|
||||
stopped = true;
|
||||
stop_value = 0;
|
||||
|
||||
if (sdf->HasElement("multiplier"))
|
||||
multiplier = sdf->Get<double>("multiplier");
|
||||
|
||||
gzmsg << "Initializing encoder: " << topic << " joint=" << joint->GetName()
|
||||
<< " radians=" << radians << " multiplier=" << multiplier << std::endl;
|
||||
|
||||
// Connect to Gazebo transport for messaging
|
||||
std::string scoped_name =
|
||||
model->GetWorld()->GetName() + "::" + model->GetScopedName();
|
||||
boost::replace_all(scoped_name, "::", "/");
|
||||
node = gazebo::transport::NodePtr(new gazebo::transport::Node());
|
||||
node->Init(scoped_name);
|
||||
command_sub = node->Subscribe(topic + "/control", &Encoder::Callback, this);
|
||||
pos_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/position");
|
||||
vel_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/velocity");
|
||||
|
||||
// Connect to the world update event.
|
||||
// This will trigger the Update function every Gazebo iteration
|
||||
updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
|
||||
boost::bind(&Encoder::Update, this, _1));
|
||||
}
|
||||
|
||||
void Encoder::Update(const gazebo::common::UpdateInfo& info) {
|
||||
gazebo::msgs::Float64 pos_msg, vel_msg;
|
||||
if (stopped) {
|
||||
pos_msg.set_data(stop_value * multiplier);
|
||||
pos_pub->Publish(pos_msg);
|
||||
vel_msg.set_data(0);
|
||||
vel_pub->Publish(vel_msg);
|
||||
} else {
|
||||
pos_msg.set_data((GetAngle() - zero) * multiplier);
|
||||
pos_pub->Publish(pos_msg);
|
||||
vel_msg.set_data(GetVelocity() * multiplier);
|
||||
vel_pub->Publish(vel_msg);
|
||||
}
|
||||
}
|
||||
|
||||
void Encoder::Callback(const gazebo::msgs::ConstStringPtr& msg) {
|
||||
std::string command = msg->data();
|
||||
if (command == "reset") {
|
||||
zero = GetAngle();
|
||||
} else if (command == "start") {
|
||||
stopped = false;
|
||||
zero = (GetAngle() - stop_value);
|
||||
} else if (command == "stop") {
|
||||
stopped = true;
|
||||
stop_value = GetAngle();
|
||||
} else {
|
||||
gzerr << "WARNING: Encoder got unknown command '" << command << "'."
|
||||
<< std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
double Encoder::GetAngle() {
|
||||
if (radians) {
|
||||
return joint->GetAngle(0).Radian();
|
||||
} else {
|
||||
return joint->GetAngle(0).Degree();
|
||||
}
|
||||
}
|
||||
|
||||
double Encoder::GetVelocity() {
|
||||
if (radians) {
|
||||
return joint->GetVelocity(0);
|
||||
} else {
|
||||
return joint->GetVelocity(0) * (180.0 / M_PI);
|
||||
}
|
||||
}
|
||||
112
simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h
Normal file
112
simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h
Normal file
@@ -0,0 +1,112 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
||||
#include <gazebo/gazebo.hh>
|
||||
#include <gazebo/physics/physics.hh>
|
||||
#include <gazebo/transport/transport.hh>
|
||||
|
||||
#include "simulation/gz_msgs/msgs.h"
|
||||
|
||||
/**
|
||||
* \brief Plugin for reading the speed and relative angle of a joint.
|
||||
*
|
||||
* This plugin publishes the angle since last reset and the speed of a
|
||||
* given joint to subtopics of the given topic every physics
|
||||
* update. There is also a control subtopic that takes three commands:
|
||||
* "start", "stop" and "reset":
|
||||
*
|
||||
* - "start": Start counting ticks from the current count.
|
||||
* - "stop": Stop counting ticks, pauses updates.
|
||||
* - "reset": Set the current angle to zero.
|
||||
*
|
||||
* To add a encoder to your robot, add the following XML to your
|
||||
* robot model:
|
||||
*
|
||||
* <plugin name="my_encoder" filename="libencoder.so">
|
||||
* <joint>Joint Name</joint>
|
||||
* <topic>~/my/topic</topic>
|
||||
* <units>{degrees, radians}</units>
|
||||
* <multiplier>Number</multiplier>
|
||||
* </plugin>
|
||||
*
|
||||
* - `joint`: Name of the joint this encoder is attached to.
|
||||
* - `topic`: Optional. Used as the root for subtopics. `topic`/position
|
||||
* (gazebo.msgs.Float64),
|
||||
* `topic`/velocity (gazebo.msgs.Float64), `topic`/control
|
||||
* (gazebo.msgs.String)
|
||||
* The suggested value for topic is of the form
|
||||
* ~/simulator/encoder/dio/<n>
|
||||
* where <n> is the number of the first digital input channel
|
||||
* used to formulate the encoder
|
||||
*
|
||||
* - `units`: Optional. Defaults to radians.
|
||||
* - `multiplier`: Optional. Defaults to 1.
|
||||
* This can be used to make the simulated encoder
|
||||
* return a comparable number of ticks to a 'real' encoder
|
||||
* Useful facts: A 'degrees' encoder will report 360 ticks/revolution.
|
||||
* The k4X encoder type can add another multiple of 4 into the mix.
|
||||
*/
|
||||
class Encoder : public gazebo::ModelPlugin {
|
||||
public:
|
||||
/// \brief Load the encoder and configures it according to the sdf.
|
||||
void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
|
||||
|
||||
/// \brief Sends out the encoder reading each timestep.
|
||||
void Update(const gazebo::common::UpdateInfo& info);
|
||||
|
||||
private:
|
||||
/// \brief Root topic for subtopics on this topic.
|
||||
std::string topic;
|
||||
|
||||
/// \brief Whether or not this encoder measures radians or degrees.
|
||||
bool radians;
|
||||
|
||||
/// \brief A factor to mulitply this output by.
|
||||
double multiplier;
|
||||
|
||||
/// \brief Whether or not the encoder has been stopped.
|
||||
bool stopped;
|
||||
|
||||
/// \brief The zero value of the encoder.
|
||||
double zero;
|
||||
|
||||
/// \brief The value the encoder stopped counting at
|
||||
double stop_value;
|
||||
|
||||
/// \brief The joint that this encoder measures
|
||||
gazebo::physics::JointPtr joint;
|
||||
|
||||
/// \brief Callback for handling control data
|
||||
void Callback(const gazebo::msgs::ConstStringPtr& msg);
|
||||
|
||||
/// \brief Gets the current angle, taking into account whether to
|
||||
/// return radians or degrees.
|
||||
double GetAngle();
|
||||
|
||||
/// \brief Gets the current velocity, taking into account whether to
|
||||
/// return radians/second or degrees/second.
|
||||
double GetVelocity();
|
||||
|
||||
/// \brief The model to which this is attached.
|
||||
gazebo::physics::ModelPtr model;
|
||||
|
||||
/// \brief Pointer to the world update function.
|
||||
gazebo::event::ConnectionPtr updateConn;
|
||||
|
||||
/// \brief The node on which we're advertising.
|
||||
gazebo::transport::NodePtr node;
|
||||
|
||||
/// \brief Subscriber handle.
|
||||
gazebo::transport::SubscriberPtr command_sub;
|
||||
|
||||
/// \brief Publisher handles.
|
||||
gazebo::transport::PublisherPtr pos_pub, vel_pub;
|
||||
};
|
||||
Reference in New Issue
Block a user