Skip to content

Commit

Permalink
fix: dart model folder + coldgas thruster
Browse files Browse the repository at this point in the history
  • Loading branch information
Pedro-Roque committed May 27, 2024
1 parent ed59d6d commit 797350b
Show file tree
Hide file tree
Showing 5 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion models/2d_spacecraft/2d_spacecraft.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
</surface>
</collision>
<visual name='body_visual'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 -1.57079</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<model>
<name>DART Spacecraft Model</name>
<version>1.0</version>
<sdf version='1.6'>3d_spacecraft.sdf</sdf>
<sdf version='1.6'>spacecraft_dart.sdf</sdf>

<author>
<name>Pedro Roque, extracted from NASA 3D Models. All rights belong ot NASA.</name>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
<geometry>
<mesh>
<scale>0.5 0.5 0.5</scale>
<uri>model://3d_spacecraft/meshes/dart.dae</uri>
<uri>model://spacecraft_dart/meshes/dart.dae</uri>
</mesh>
</geometry>
</visual>
Expand Down
8 changes: 4 additions & 4 deletions src/gazebo_coldgas_thruster_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ void GazeboColdGasThrusterPlugin::OnUpdate(const common::UpdateInfo& _info) {

// Calculate sampling time instant within the cycle
sampling_time_ = _info.simTime.Double() - cycle_start_time_;
if (motor_number_ == 0 & DEBUG) std::cout << "PWM Period: " << 1.0/pwm_frequency_ << " Cycle Start time: " << cycle_start_time_ << " Sampling time: " << sampling_time_;
if (DEBUG) std::cout << motor_number_ << ": PWM Period: " << 1.0/pwm_frequency_ << " Cycle Start time: " << cycle_start_time_ << " Sampling time: " << sampling_time_ << std::endl;
UpdateForcesAndMoments(ref_duty_cycle_ * (1.0 / pwm_frequency_), sampling_time_);
}

Expand All @@ -103,15 +103,15 @@ void GazeboColdGasThrusterPlugin::VelocityCallback(CommandMotorSpeedPtr &rot_vel
std::cout << "You tried to access index " << motor_number_
<< " of the MotorSpeed message array which is of size " << rot_velocities->motor_speed_size() << "." << std::endl;
} else {
ref_duty_cycle_ = std::min(static_cast<double>(rot_velocities->motor_speed(motor_number_)), 1.0);
if (motor_number_ == 0 && DEBUG) std::cout << "Processed ref duty cycle: " << ref_duty_cycle_ << " Received value: " << rot_velocities->motor_speed(motor_number_) << std::endl;
ref_duty_cycle_ = std::min(static_cast<double>((rot_velocities->motor_speed(motor_number_))), 1.0);
if (DEBUG) std::cout << motor_number_ << ": Processed ref duty cycle: " << ref_duty_cycle_ << " Received value: " << rot_velocities->motor_speed(motor_number_) << std::endl;
}
}

void GazeboColdGasThrusterPlugin::UpdateForcesAndMoments(const double &ref_duty_cycle_, const double &sampling_time_) {
// Thrust is only generated uring the duty cycle
double force = sampling_time_ <= ref_duty_cycle_ ? max_thrust_ : 0.0;
if (motor_number_ == 0 && DEBUG) std::cout << "Force: " << force << " Sampling time: " << sampling_time_ << " Ref duty cycle: " << ref_duty_cycle_ << std::endl;
if (DEBUG) std::cout << motor_number_ << ": Force: " << force << " Sampling time: " << sampling_time_ << " Ref duty cycle: " << ref_duty_cycle_ << std::endl;
link_->AddRelativeForce(ignition::math::Vector3d(0, 0, force));
}

Expand Down

0 comments on commit 797350b

Please sign in to comment.