Program Listing for File gimbal.hpp
↰ Return to documentation for file (include/psdk_wrapper/modules/gimbal.hpp
)
/*
* Copyright (C) 2024 Unmanned Life
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#ifndef PSDK_WRAPPER_INCLUDE_PSDK_WRAPPER_MODULES_GIMBAL_HPP_
#define PSDK_WRAPPER_INCLUDE_PSDK_WRAPPER_MODULES_GIMBAL_HPP_
#include <dji_gimbal_manager.h> //NOLINT
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <string>
#include "psdk_interfaces/msg/gimbal_rotation.hpp"
#include "psdk_interfaces/srv/gimbal_reset.hpp"
#include "psdk_interfaces/srv/gimbal_set_mode.hpp"
#include "psdk_wrapper/utils/psdk_wrapper_utils.hpp"
namespace psdk_ros2
{
class GimbalModule : public rclcpp_lifecycle::LifecycleNode
{
public:
using GimbalSetMode = psdk_interfaces::srv::GimbalSetMode;
using GimbalReset = psdk_interfaces::srv::GimbalReset;
explicit GimbalModule(const std::string& name);
~GimbalModule();
CallbackReturn on_configure(const rclcpp_lifecycle::State& state);
CallbackReturn on_activate(const rclcpp_lifecycle::State& state);
CallbackReturn on_cleanup(const rclcpp_lifecycle::State& state);
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& state);
CallbackReturn on_shutdown(const rclcpp_lifecycle::State& state);
bool init();
bool deinit();
private:
void gimbal_rotation_cb(
const psdk_interfaces::msg::GimbalRotation::SharedPtr msg);
void gimbal_set_mode_cb(
const std::shared_ptr<GimbalSetMode::Request> request,
const std::shared_ptr<GimbalSetMode::Response> response);
void gimbal_reset_cb(const std::shared_ptr<GimbalReset::Request> request,
const std::shared_ptr<GimbalReset::Response> response);
rclcpp::Subscription<psdk_interfaces::msg::GimbalRotation>::SharedPtr
gimbal_rotation_sub_;
rclcpp::Service<GimbalSetMode>::SharedPtr gimbal_set_mode_service_;
rclcpp::Service<GimbalReset>::SharedPtr gimbal_reset_service_;
const rmw_qos_profile_t& qos_profile_{rmw_qos_profile_services_default};
bool is_module_initialized_{false};
};
} // namespace psdk_ros2
#endif // PSDK_WRAPPER_INCLUDE_PSDK_WRAPPER_MODULES_GIMBAL_HPP_