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

change we control #111

Open
wants to merge 2 commits into
base: kinetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
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
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,14 @@
#include <hector_uav_msgs/MotorStatus.h>
#include <hector_uav_msgs/EnableMotors.h>

#include <gazebo_ros_control/default_robot_hw_sim.h>

namespace hector_quadrotor_controller_gazebo
{

using namespace hector_quadrotor_interface;

class QuadrotorHardwareSim : public gazebo_ros_control::RobotHWSim
class QuadrotorHardwareSim : public gazebo_ros_control::DefaultRobotHWSim
{
public:
QuadrotorHardwareSim();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ bool QuadrotorHardwareSim::initSim(
std::vector<transmission_interface::TransmissionInfo> transmissions)
{
// store parent model pointer
gazebo_ros_control::DefaultRobotHWSim::initSim(robot_namespace,model_nh,parent_model,urdf_model,transmissions);
StefanFabian marked this conversation as resolved.
Show resolved Hide resolved
model_ = parent_model;
link_ = model_->GetLink();
#if (GAZEBO_MAJOR_VERSION >= 8)
Expand Down Expand Up @@ -118,6 +119,7 @@ bool QuadrotorHardwareSim::initSim(
void QuadrotorHardwareSim::readSim(ros::Time time, ros::Duration period)
{
// read state from Gazebo
gazebo_ros_control::DefaultRobotHWSim::readSim(time,period);
const double acceleration_time_constant = 0.1;
#if (GAZEBO_MAJOR_VERSION >= 8)
gz_acceleration_ = ((link_->WorldLinearVel() - gz_velocity_) + acceleration_time_constant * gz_acceleration_) /
Expand Down Expand Up @@ -232,6 +234,7 @@ void QuadrotorHardwareSim::readSim(ros::Time time, ros::Duration period)

void QuadrotorHardwareSim::writeSim(ros::Time time, ros::Duration period)
{
gazebo_ros_control::DefaultRobotHWSim::writeSim(time,period);
bool result_written = false;

if (motor_output_->connected() && motor_output_->enabled()) {
Expand Down