summaryrefslogtreecommitdiff
path: root/microstrain-inertial-driver-fix_error_no_define.patch
diff options
context:
space:
mode:
Diffstat (limited to 'microstrain-inertial-driver-fix_error_no_define.patch')
-rw-r--r--microstrain-inertial-driver-fix_error_no_define.patch67
1 files changed, 67 insertions, 0 deletions
diff --git a/microstrain-inertial-driver-fix_error_no_define.patch b/microstrain-inertial-driver-fix_error_no_define.patch
new file mode 100644
index 0000000..72729ab
--- /dev/null
+++ b/microstrain-inertial-driver-fix_error_no_define.patch
@@ -0,0 +1,67 @@
+diff -Naur ros-humble-microstrain-inertial-driver-3.0.1_org/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/services.h ros-humble-microstrain-inertial-driver-3.0.1/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/services.h
+--- ros-humble-microstrain-inertial-driver-3.0.1_org/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/services.h 2023-02-11 05:19:58.000000000 +0800
++++ ros-humble-microstrain-inertial-driver-3.0.1/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/services.h 2023-10-21 17:04:27.000000000 +0800
+@@ -172,7 +172,12 @@
+ * \return Pointer to an initialized service
+ */
+ template<typename ServiceType>
+- typename RosServiceType<ServiceType>::SharedPtr configureService(const std::string& name, bool (Services::*callback)(typename ServiceType::Request&, typename ServiceType::Response&));
++ typename RosServiceType<ServiceType>::SharedPtr configureService(const std::string& name, bool (Services::*callback)(typename ServiceType::Request&, typename ServiceType::Response&))
++{
++ MICROSTRAIN_DEBUG(node_, "Configuring service %s", name.c_str());
++ return createService<ServiceType>(node_, name, callback, this);
++}
++
+
+ /**
+ * \brief Configures a MIP command dependent service. This service will only be configured if the device supports the command
+@@ -184,7 +189,19 @@
+ * \return Pointer to an initialized service, or nullptr if the device does not support the MipType
+ */
+ template<typename ServiceType, typename MipType, uint8_t DescriptorSet = MipType::DESCRIPTOR_SET>
+- typename RosServiceType<ServiceType>::SharedPtr configureService(const std::string& name, bool (Services::*callback)(typename ServiceType::Request&, typename ServiceType::Response&));
++ typename RosServiceType<ServiceType>::SharedPtr configureService(const std::string& name, bool (Services::*callback)(typename ServiceType::Request&, typename ServiceType::Response&))
++{
++ if (config_->mip_device_->supportsDescriptor(DescriptorSet, MipType::FIELD_DESCRIPTOR))
++ {
++ MICROSTRAIN_DEBUG(node_, "Configuring service %s to execute MIP command 0x%02x%02x", name.c_str(), DescriptorSet, MipType::FIELD_DESCRIPTOR);
++ return createService<ServiceType>(node_, name, callback, this);
++ }
++ else
++ {
++ MICROSTRAIN_DEBUG(node_, "Device does not support the %s service because the device does not support descriptor 0x%02x%02x", name.c_str(), DescriptorSet, MipType::FIELD_DESCRIPTOR);
++ return nullptr;
++ }
++}
+
+ // Handles to the ROS node and the config
+ RosNodeType* node_;
+@@ -253,27 +270,8 @@
+ RosServiceType<SetFilterSpeedLeverArmServiceMsg>::SharedPtr set_filter_speed_lever_arm_service_;
+ };
+
+-template<typename ServiceType>
+-typename RosServiceType<ServiceType>::SharedPtr Services::configureService(const std::string& name, bool (Services::*callback)(typename ServiceType::Request&, typename ServiceType::Response&))
+-{
+- MICROSTRAIN_DEBUG(node_, "Configuring service %s", name.c_str());
+- return createService<ServiceType>(node_, name, callback, this);
+-}
+
+-template<typename ServiceType, typename MipType, uint8_t DescriptorSet = MipType::DESCRIPTOR_SET>
+-typename RosServiceType<ServiceType>::SharedPtr Services::configureService(const std::string& name, bool (Services::*callback)(typename ServiceType::Request&, typename ServiceType::Response&))
+-{
+- if (config_->mip_device_->supportsDescriptor(DescriptorSet, MipType::FIELD_DESCRIPTOR))
+- {
+- MICROSTRAIN_DEBUG(node_, "Configuring service %s to execute MIP command 0x%02x%02x", name.c_str(), DescriptorSet, MipType::FIELD_DESCRIPTOR);
+- return createService<ServiceType>(node_, name, callback, this);
+- }
+- else
+- {
+- MICROSTRAIN_DEBUG(node_, "Device does not support the %s service because the device does not support descriptor 0x%02x%02x", name.c_str(), DescriptorSet, MipType::FIELD_DESCRIPTOR);
+- return nullptr;
+- }
+-}
++
+
+ } // namespace microstrain
+