@@ -87,7 +87,7 @@ void Driver::processMessage(const can_msgs::msg::Frame::SharedPtr received_msg)
87
87
return ;
88
88
}
89
89
90
- Field* field = nullptr ;
90
+ Field* field = nullptr ;
91
91
uint32_t received_api = getApi (*received_msg);
92
92
if ((received_api & CAN_MSGID_API_M & CAN_API_MC_CFG) == CAN_API_MC_CFG)
93
93
{
@@ -142,8 +142,8 @@ void Driver::sendId(const uint32_t id)
142
142
void Driver::sendUint8 (const uint32_t id, const uint8_t value)
143
143
{
144
144
can_msgs::msg::Frame msg = getMsg (id);
145
- msg.dlc = sizeof (uint8_t );
146
- uint8_t data[8 ] = { 0 };
145
+ msg.dlc = sizeof (uint8_t );
146
+ uint8_t data[8 ] = { 0 };
147
147
std::memcpy (data, &value, sizeof (uint8_t ));
148
148
std::copy (std::begin (data), std::end (data), std::begin (msg.data ));
149
149
@@ -153,8 +153,8 @@ void Driver::sendUint8(const uint32_t id, const uint8_t value)
153
153
void Driver::sendUint16 (const uint32_t id, const uint16_t value)
154
154
{
155
155
can_msgs::msg::Frame msg = getMsg (id);
156
- msg.dlc = sizeof (uint16_t );
157
- uint8_t data[8 ] = { 0 };
156
+ msg.dlc = sizeof (uint16_t );
157
+ uint8_t data[8 ] = { 0 };
158
158
std::memcpy (data, &value, sizeof (uint16_t ));
159
159
std::copy (std::begin (data), std::end (data), std::begin (msg.data ));
160
160
@@ -164,10 +164,10 @@ void Driver::sendUint16(const uint32_t id, const uint16_t value)
164
164
void Driver::sendFixed8x8 (const uint32_t id, const float value)
165
165
{
166
166
can_msgs::msg::Frame msg = getMsg (id);
167
- msg.dlc = sizeof (int16_t );
168
- int16_t output_value = static_cast <int16_t >(static_cast <float >(1 << 8 ) * value);
167
+ msg.dlc = sizeof (int16_t );
168
+ int16_t output_value = static_cast <int16_t >(static_cast <float >(1 << 8 ) * value);
169
169
170
- uint8_t data[8 ] = { 0 };
170
+ uint8_t data[8 ] = { 0 };
171
171
std::memcpy (data, &output_value, sizeof (int16_t ));
172
172
std::copy (std::begin (data), std::end (data), std::begin (msg.data ));
173
173
@@ -177,10 +177,10 @@ void Driver::sendFixed8x8(const uint32_t id, const float value)
177
177
void Driver::sendFixed16x16 (const uint32_t id, const double value)
178
178
{
179
179
can_msgs::msg::Frame msg = getMsg (id);
180
- msg.dlc = sizeof (int32_t );
181
- int32_t output_value = static_cast <int32_t >(static_cast <double >((1 << 16 ) * value));
180
+ msg.dlc = sizeof (int32_t );
181
+ int32_t output_value = static_cast <int32_t >(static_cast <double >((1 << 16 ) * value));
182
182
183
- uint8_t data[8 ] = { 0 };
183
+ uint8_t data[8 ] = { 0 };
184
184
std::memcpy (data, &output_value, sizeof (int32_t ));
185
185
std::copy (std::begin (data), std::end (data), std::begin (msg.data ));
186
186
@@ -190,10 +190,10 @@ void Driver::sendFixed16x16(const uint32_t id, const double value)
190
190
can_msgs::msg::Frame Driver::getMsg (const uint32_t id)
191
191
{
192
192
can_msgs::msg::Frame msg;
193
- msg.id = id;
194
- msg.dlc = 0 ;
195
- msg.is_extended = true ;
196
- msg.header .stamp = nh_->get_clock ()->now ();
193
+ msg.id = id;
194
+ msg.dlc = 0 ;
195
+ msg.is_extended = true ;
196
+ msg.header .stamp = nh_->get_clock ()->now ();
197
197
msg.header .frame_id = " base_link" ;
198
198
return msg;
199
199
}
@@ -437,7 +437,7 @@ void Driver::verifyParams()
437
437
RCLCPP_INFO (rclcpp::get_logger (" rclcpp" ), " Puma Motor Controller on %s (%i): all parameters verified." ,
438
438
device_name_.c_str (), device_number_);
439
439
configured_ = true ;
440
- state_ = ConfigurationState::Configured;
440
+ state_ = ConfigurationState::Configured;
441
441
}
442
442
}
443
443
@@ -663,13 +663,13 @@ void Driver::requestFeedbackSetpoint()
663
663
void Driver::resetConfiguration ()
664
664
{
665
665
configured_ = false ;
666
- state_ = ConfigurationState::Initializing;
666
+ state_ = ConfigurationState::Initializing;
667
667
}
668
668
669
669
void Driver::updateGains ()
670
670
{
671
671
configured_ = false ;
672
- state_ = ConfigurationState::PGain;
672
+ state_ = ConfigurationState::PGain;
673
673
}
674
674
675
675
bool Driver::receivedDutyCycle ()
@@ -786,77 +786,77 @@ bool Driver::receivedPositionSetpoint()
786
786
787
787
float Driver::lastDutyCycle ()
788
788
{
789
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_VOLTOUT)));
789
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_VOLTOUT)));
790
790
field->received = false ;
791
791
return field->interpretFixed8x8 () / 128.0 ;
792
792
}
793
793
794
794
float Driver::lastBusVoltage ()
795
795
{
796
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_VOLTBUS)));
796
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_VOLTBUS)));
797
797
field->received = false ;
798
798
return field->interpretFixed8x8 ();
799
799
}
800
800
801
801
float Driver::lastCurrent ()
802
802
{
803
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_CURRENT)));
803
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_CURRENT)));
804
804
field->received = false ;
805
805
return field->interpretFixed8x8 ();
806
806
}
807
807
808
808
double Driver::lastPosition ()
809
809
{
810
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_POS)));
810
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_POS)));
811
811
field->received = false ;
812
812
return field->interpretFixed16x16 () * ((2 * M_PI) / gear_ratio_); // Convert rev to rad
813
813
}
814
814
815
815
double Driver::lastSpeed ()
816
816
{
817
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_SPD)));
817
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_SPD)));
818
818
field->received = false ;
819
819
return field->interpretFixed16x16 () * ((2 * M_PI) / (gear_ratio_ * 60 )); // Convert RPM to rad/s
820
820
}
821
821
822
822
uint8_t Driver::lastFault ()
823
823
{
824
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_FAULT)));
824
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_FAULT)));
825
825
field->received = false ;
826
826
return field->data [0 ];
827
827
}
828
828
829
829
uint8_t Driver::lastPower ()
830
830
{
831
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_POWER)));
831
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_POWER)));
832
832
field->received = false ;
833
833
return field->data [0 ];
834
834
}
835
835
836
836
uint8_t Driver::lastMode ()
837
837
{
838
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_CMODE)));
838
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_CMODE)));
839
839
field->received = false ;
840
840
return field->data [0 ];
841
841
}
842
842
843
843
float Driver::lastOutVoltage ()
844
844
{
845
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_VOUT)));
845
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_VOUT)));
846
846
field->received = false ;
847
847
return field->interpretFixed8x8 ();
848
848
}
849
849
850
850
float Driver::lastTemperature ()
851
851
{
852
- Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_TEMP)));
852
+ Field* field = statusFieldForMessage (getApi (getMsg (LM_API_STATUS_TEMP)));
853
853
field->received = false ;
854
854
return field->interpretFixed8x8 ();
855
855
}
856
856
857
857
float Driver::lastAnalogInput ()
858
858
{
859
- Field* field = statusFieldForMessage (getApi (getMsg (CPR_API_STATUS_ANALOG)));
859
+ Field* field = statusFieldForMessage (getApi (getMsg (CPR_API_STATUS_ANALOG)));
860
860
field->received = false ;
861
861
return field->interpretFixed8x8 ();
862
862
}
@@ -884,28 +884,28 @@ double Driver::lastSetpoint()
884
884
}
885
885
double Driver::statusSpeedGet ()
886
886
{
887
- Field* field = spdFieldForMessage (getApi (getMsg (LM_API_SPD_SET)));
887
+ Field* field = spdFieldForMessage (getApi (getMsg (LM_API_SPD_SET)));
888
888
field->received = false ;
889
889
return field->interpretFixed16x16 () * ((2 * M_PI) / (gear_ratio_ * 60 )); // Convert RPM to rad/s
890
890
}
891
891
892
892
float Driver::statusDutyCycleGet ()
893
893
{
894
- Field* field = voltageFieldForMessage (getApi (getMsg (LM_API_VOLT_SET)));
894
+ Field* field = voltageFieldForMessage (getApi (getMsg (LM_API_VOLT_SET)));
895
895
field->received = false ;
896
896
return field->interpretFixed8x8 () / 128.0 ;
897
897
}
898
898
899
899
float Driver::statusCurrentGet ()
900
900
{
901
- Field* field = ictrlFieldForMessage (getApi (getMsg (LM_API_ICTRL_SET)));
901
+ Field* field = ictrlFieldForMessage (getApi (getMsg (LM_API_ICTRL_SET)));
902
902
field->received = false ;
903
903
return field->interpretFixed8x8 ();
904
904
}
905
905
906
906
double Driver::statusPositionGet ()
907
907
{
908
- Field* field = posFieldForMessage (getApi (getMsg (LM_API_POS_SET)));
908
+ Field* field = posFieldForMessage (getApi (getMsg (LM_API_POS_SET)));
909
909
field->received = false ;
910
910
return field->interpretFixed16x16 () * ((2 * M_PI) / gear_ratio_); // Convert rev to rad
911
911
}
0 commit comments