

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
... | ... | @@ -26,6 +26,10 @@ |
26 | 26 |
'hw_type', default_value=TextSubstitution(text='DualSense')) |
27 | 27 |
topic_name_arg = DeclareLaunchArgument( |
28 | 28 |
'topic_name', default_value=TextSubstitution(text='cmd_vel')) |
29 |
+ linear_speed_arg = DeclareLaunchArgument( |
|
30 |
+ 'linear_speed', default_value=TextSubstitution(text='0.2')) |
|
31 |
+ angular_speed_arg = DeclareLaunchArgument( |
|
32 |
+ 'angular_speed', default_value=TextSubstitution(text='0.6')) |
|
29 | 33 |
|
30 | 34 |
joy_container = ComposableNodeContainer( |
31 | 35 |
name='joy_container', |
... | ... | @@ -45,7 +49,9 @@ |
45 | 49 |
name='teleop_twist_joy_node', |
46 | 50 |
namespace='', |
47 | 51 |
parameters=[{ |
48 |
- 'hw_type': LaunchConfiguration('hw_type') |
|
52 |
+ 'hw_type': LaunchConfiguration('hw_type'), |
|
53 |
+ 'linear_speed': LaunchConfiguration('linear_speed'), |
|
54 |
+ 'angular_speed': LaunchConfiguration('angular_speed') |
|
49 | 55 |
}], |
50 | 56 |
remappings=[ |
51 | 57 |
('cmd_vel', LaunchConfiguration('topic_name')) |
... | ... | @@ -58,6 +64,8 @@ |
58 | 64 |
|
59 | 65 |
ld.add_action(hw_type_arg) |
60 | 66 |
ld.add_action(topic_name_arg) |
67 |
+ ld.add_action(linear_speed_arg) |
|
68 |
+ ld.add_action(angular_speed_arg) |
|
61 | 69 |
|
62 | 70 |
ld.add_action(joy_container) |
63 | 71 |
|
--- p9n_node/src/teleop_twist_joy_node.cpp
+++ p9n_node/src/teleop_twist_joy_node.cpp
... | ... | @@ -68,7 +68,12 @@ |
68 | 68 |
if (this->p9n_if_->isTiltedStickL()) { |
69 | 69 |
auto twist_msg = std::make_unique<Twist>(); |
70 | 70 |
twist_msg->linear.set__x(this->linear_max_speed_ * this->p9n_if_->tiltedStickLY()); |
71 |
- twist_msg->angular.set__z(this->angular_max_speed_ * this->p9n_if_->tiltedStickLX()); |
|
71 |
+ |
|
72 |
+ if (twist_msg->linear.x > 0) { |
|
73 |
+ twist_msg->angular.set__z(this->angular_max_speed_ * this->p9n_if_->tiltedStickLX()); |
|
74 |
+ } else { |
|
75 |
+ twist_msg->angular.set__z(-this->angular_max_speed_ * this->p9n_if_->tiltedStickLX()); |
|
76 |
+ } |
|
72 | 77 |
this->twist_pub_->publish(std::move(twist_msg)); |
73 | 78 |
|
74 | 79 |
stopped = false; |
Add a comment
Delete comment
Once you delete this comment, you won't be able to recover it. Are you sure you want to delete this comment?