@@ -178,6 +178,9 @@ class gz::sim::systems::LinearBatteryPluginPrivate
178
178
179
179
// / \brief Initial power load set trough config
180
180
public: double initialPowerLoad = 0.0 ;
181
+
182
+ // / \brief Flag to invert the current sign
183
+ public: bool invertCurrentSign{false };
181
184
};
182
185
183
186
// ///////////////////////////////////////////////
@@ -273,6 +276,10 @@ void LinearBatteryPlugin::Configure(const Entity &_entity,
273
276
if (_sdf->HasElement (" fix_issue_225" ))
274
277
this ->dataPtr ->fixIssue225 = _sdf->Get <bool >(" fix_issue_225" );
275
278
279
+ if (_sdf->HasElement (" invert_current_sign" ))
280
+ this ->dataPtr ->invertCurrentSign =
281
+ _sdf->Get <bool >(" invert_current_sign" );
282
+
276
283
if (_sdf->HasElement (" battery_name" ) && _sdf->HasElement (" voltage" ))
277
284
{
278
285
this ->dataPtr ->batteryName = _sdf->Get <std::string>(" battery_name" );
@@ -624,7 +631,10 @@ void LinearBatteryPlugin::PostUpdate(const UpdateInfo &_info,
624
631
msg.mutable_header ()->mutable_stamp ()->CopyFrom (
625
632
convert<msgs::Time>(_info.simTime ));
626
633
msg.set_voltage (this ->dataPtr ->battery ->Voltage ());
627
- msg.set_current (this ->dataPtr ->ismooth );
634
+ if (this ->dataPtr ->invertCurrentSign )
635
+ msg.set_current (-this ->dataPtr ->ismooth );
636
+ else
637
+ msg.set_current (this ->dataPtr ->ismooth );
628
638
msg.set_charge (this ->dataPtr ->q );
629
639
msg.set_capacity (this ->dataPtr ->c );
630
640
0 commit comments