diff --git a/src/gazebo_motor_model.cpp b/src/gazebo_motor_model.cpp index f05edc5d09..6bfd837bda 100644 --- a/src/gazebo_motor_model.cpp +++ b/src/gazebo_motor_model.cpp @@ -33,8 +33,7 @@ void GazeboMotorModel::InitializeParams() {} void GazeboMotorModel::Publish() { turning_velocity_msg_.set_data(joint_->GetVelocity(0)); - // FIXME: Commented out to prevent warnings about queue limit reached. - // motor_velocity_pub_->Publish(turning_velocity_msg_); + motor_velocity_pub_->Publish(turning_velocity_msg_); } void GazeboMotorModel::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) { @@ -152,8 +151,7 @@ void GazeboMotorModel::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) { command_sub_ = node_handle_->Subscribe("~/" + model_->GetName() + command_sub_topic_, &GazeboMotorModel::VelocityCallback, this); //std::cout << "[gazebo_motor_model]: Subscribe to gz topic: "<< motor_failure_sub_topic_ << std::endl; motor_failure_sub_ = node_handle_->Subscribe(motor_failure_sub_topic_, &GazeboMotorModel::MotorFailureCallback, this); - // FIXME: Commented out to prevent warnings about queue limit reached. - //motor_velocity_pub_ = node_handle_->Advertise("~/" + model_->GetName() + motor_speed_pub_topic_, 1); + motor_velocity_pub_ = node_handle_->Advertise("~/" + model_->GetName() + motor_speed_pub_topic_, 10); wind_sub_ = node_handle_->Subscribe("~/" + wind_sub_topic_, &GazeboMotorModel::WindVelocityCallback, this); // Create the first order filter.