WATANABE Aoi 2023-09-19
Merge pull request #34 from HarvestX/feat/add-param
add apram and fix
@bde70deee1c534603b11f4b7aee6c0d643b37f19
p9n_bringup/launch/teleop.launch.py
--- p9n_bringup/launch/teleop.launch.py
+++ p9n_bringup/launch/teleop.launch.py
@@ -26,6 +26,10 @@
         'hw_type', default_value=TextSubstitution(text='DualSense'))
     topic_name_arg = DeclareLaunchArgument(
         'topic_name', default_value=TextSubstitution(text='cmd_vel'))
+    linear_speed_arg = DeclareLaunchArgument(
+        'linear_speed', default_value=TextSubstitution(text='0.2'))
+    angular_speed_arg = DeclareLaunchArgument(
+        'angular_speed', default_value=TextSubstitution(text='0.6'))
 
     joy_container = ComposableNodeContainer(
         name='joy_container',
@@ -45,7 +49,9 @@
                 name='teleop_twist_joy_node',
                 namespace='',
                 parameters=[{
-                        'hw_type': LaunchConfiguration('hw_type')
+                        'hw_type': LaunchConfiguration('hw_type'),
+                        'linear_speed': LaunchConfiguration('linear_speed'),
+                        'angular_speed': LaunchConfiguration('angular_speed')
                 }],
                 remappings=[
                     ('cmd_vel', LaunchConfiguration('topic_name'))
@@ -58,6 +64,8 @@
 
     ld.add_action(hw_type_arg)
     ld.add_action(topic_name_arg)
+    ld.add_action(linear_speed_arg)
+    ld.add_action(angular_speed_arg)
 
     ld.add_action(joy_container)
 
p9n_node/src/teleop_twist_joy_node.cpp
--- p9n_node/src/teleop_twist_joy_node.cpp
+++ p9n_node/src/teleop_twist_joy_node.cpp
@@ -68,7 +68,12 @@
   if (this->p9n_if_->isTiltedStickL()) {
     auto twist_msg = std::make_unique<Twist>();
     twist_msg->linear.set__x(this->linear_max_speed_ * this->p9n_if_->tiltedStickLY());
-    twist_msg->angular.set__z(this->angular_max_speed_ * this->p9n_if_->tiltedStickLX());
+
+    if (twist_msg->linear.x > 0) {
+      twist_msg->angular.set__z(this->angular_max_speed_ * this->p9n_if_->tiltedStickLX());
+    } else {
+      twist_msg->angular.set__z(-this->angular_max_speed_ * this->p9n_if_->tiltedStickLX());
+    }
     this->twist_pub_->publish(std::move(twist_msg));
 
     stopped = false;
Add a comment
List