setup joy

This commit is contained in:
acki
2025-12-18 19:14:39 +01:00
parent c2f967aee7
commit ca9da5b1e1
3 changed files with 10 additions and 1 deletions

View File

@@ -37,7 +37,7 @@ set(strat_fsm_sources
)
add_executable(strat_fsm ${strat_fsm_sources})
ament_target_dependencies(strat_fsm rclcpp std_msgs std_srvs modelec_interfaces ament_index_cpp)
ament_target_dependencies(strat_fsm rclcpp std_msgs sensor_msgs std_srvs modelec_interfaces ament_index_cpp)
target_link_libraries(strat_fsm modelec_utils::utils modelec_utils::config)
target_include_directories(strat_fsm PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>

View File

@@ -7,6 +7,8 @@
#include <modelec_interfaces/msg/action_servo_timed_array.hpp>
#include <modelec_interfaces/msg/action_exec.hpp>
#include <sensor_msgs/msg/joy.hpp>
namespace Modelec
{
class BaseAction;
@@ -60,6 +62,7 @@ namespace Modelec
rclcpp::Subscription<modelec_interfaces::msg::ActionServoTimedArray>::SharedPtr servo_timed_move_res_sub_;
rclcpp::Subscription<modelec_interfaces::msg::ActionExec>::SharedPtr action_exec_sub_;
rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr joy_sub_;
std::shared_ptr<BaseAction> action_;

View File

@@ -79,6 +79,12 @@ namespace Modelec
step_running_ -= msg->items.size();
Update();
});
joy_sub_ = node_->create_subscription<sensor_msgs::msg::Joy>(
"/joy", 10, [this](const sensor_msgs::msg::Joy::SharedPtr)
{
// use game controller to manually control all the action. make it carefully
});
}
rclcpp::Node::SharedPtr ActionExecutor::GetNode() const