Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Joy teleop fix #29

Merged
merged 2 commits into from
Aug 14, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions clearpath_control/config/a200/teleop_logitech.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
# D-pad Horiz. 6
# D-pad Vert. 7

joy_teleop/teleop_twist_joy_node:
teleop_twist_joy_node:
ros__parameters:
use_sim_time: False
axis_linear.x: 1
Expand All @@ -52,7 +52,7 @@ joy_teleop/teleop_twist_joy_node:
scale_angular_turbo.yaw: 1.2
enable_button: 4
enable_turbo_button: 5
joy_teleop/joy_node:
joy_node:
ros__parameters:
use_sim_time: False
deadzone: 0.1
Expand Down
4 changes: 2 additions & 2 deletions clearpath_control/config/a200/teleop_ps4.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@
# Accel y 6
# Accel z 8

joy_teleop/teleop_twist_joy_node:
teleop_twist_joy_node:
ros__parameters:
use_sim_time: False
axis_linear.x: 1
Expand All @@ -65,7 +65,7 @@ joy_teleop/teleop_twist_joy_node:
scale_angular_turbo.yaw: 1.2
enable_button: 4
enable_turbo_button: 5
joy_teleop/joy_node:
joy_node:
ros__parameters:
use_sim_time: False
deadzone: 0.1
Expand Down
4 changes: 2 additions & 2 deletions clearpath_control/config/j100/teleop_logitech.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
# D-pad Horiz. 6
# D-pad Vert. 7

joy_teleop/teleop_twist_joy_node:
teleop_twist_joy_node:
ros__parameters:
use_sim_time: False
axis_linear.x: 1
Expand All @@ -52,7 +52,7 @@ joy_teleop/teleop_twist_joy_node:
scale_angular_turbo.yaw: 1.4
enable_button: 4
enable_turbo_button: 5
joy_teleop/joy_node:
joy_node:
ros__parameters:
use_sim_time: False
deadzone: 0.1
Expand Down
4 changes: 2 additions & 2 deletions clearpath_control/config/j100/teleop_ps4.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@
# Accel y 6
# Accel z 8

joy_teleop/teleop_twist_joy_node:
teleop_twist_joy_node:
ros__parameters:
use_sim_time: False
axis_linear.x: 1
Expand All @@ -65,7 +65,7 @@ joy_teleop/teleop_twist_joy_node:
scale_angular_turbo.yaw: 1.4
enable_button: 4
enable_turbo_button: 5
joy_teleop/joy_node:
joy_node:
ros__parameters:
use_sim_time: False
deadzone: 0.1
Expand Down
10 changes: 7 additions & 3 deletions clearpath_control/launch/teleop_joy.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,6 @@ def generate_launch_description():
]

node_joy = Node(
namespace='joy_teleop',
package='joy_linux',
executable='joy_linux_node',
output='screen',
Expand All @@ -79,18 +78,23 @@ def generate_launch_description():
('/diagnostics', 'diagnostics'),
('/tf', 'tf'),
('/tf_static', 'tf_static'),
('joy', 'joy_teleop/joy'),
('joy/set_feedback', 'joy_teleop/joy/set_feedback'),
]
)

node_teleop_twist_joy = Node(
namespace='joy_teleop',
package='teleop_twist_joy',
executable='teleop_node',
output='screen',
name='teleop_twist_joy_node',
parameters=[
config_teleop_joy,
{'use_sim_time': use_sim_time}]
{'use_sim_time': use_sim_time}],
remappings=[
('joy', 'joy_teleop/joy'),
('cmd_vel', 'joy_teleop/cmd_vel'),
]
)

ld = LaunchDescription()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,5 +65,5 @@ def write_obj(self, key: str, obj: object, indent_level=1):
def write_file(self):
ros_parameters = self.param_file.to_ros_parameters()
for k in ros_parameters:
self.write_obj(k, ros_parameters[k])
self.write_obj(k, ros_parameters[k], indent_level=0)
self.file.close()