Compare commits

...

30 Commits

Author SHA1 Message Date
Your Name
243cd85a15 update 2025-01-20 14:37:26 +01:00
Your Name
e39573f1f2 update 2025-01-20 14:26:06 +01:00
Your Name
e43ffd6023 update 2025-01-20 14:19:30 +01:00
Your Name
2fc14276db update 2025-01-20 14:13:47 +01:00
Your Name
a762b0a4df udate 2025-01-20 14:12:19 +01:00
Your Name
b30714abb2 update 2025-01-20 14:11:26 +01:00
Your Name
6b08081658 update 2025-01-20 14:11:10 +01:00
Your Name
9127c26fc8 update 2025-01-20 14:10:28 +01:00
Your Name
d19d2f472c update 2025-01-20 14:08:41 +01:00
Your Name
aa70bd7b72 update 2025-01-20 14:07:52 +01:00
Your Name
1fbe0fb958 update 2025-01-20 14:06:07 +01:00
Your Name
5e95bc7462 update 2025-01-20 14:05:44 +01:00
Your Name
68c1657d2e update 2025-01-20 14:04:20 +01:00
Your Name
43e707d01b update 2025-01-20 14:02:40 +01:00
Your Name
7fe399bcf6 update 2025-01-20 14:00:54 +01:00
Your Name
649a2506e7 update 2025-01-20 13:53:11 +01:00
Your Name
ccb53fd48e update 2025-01-20 13:50:50 +01:00
Your Name
f45539e535 update 2025-01-20 13:41:15 +01:00
Your Name
db7cc6bb60 update 2025-01-20 13:40:04 +01:00
Your Name
27f07e164c update 2025-01-20 13:32:17 +01:00
Your Name
2137e62dc9 update 2025-01-20 12:46:43 +01:00
Your Name
4764918dec update 2025-01-20 12:45:26 +01:00
Your Name
e1663cb488 update 2025-01-20 12:37:46 +01:00
Your Name
b347a2adc9 update 2025-01-20 12:33:04 +01:00
Your Name
936bd2f9b7 update 2025-01-20 12:28:14 +01:00
Your Name
0a8408ff69 update 2025-01-20 12:21:30 +01:00
Your Name
a68304c8fd update 2025-01-20 12:16:10 +01:00
Your Name
92eeff6e2a update 2025-01-20 12:14:04 +01:00
Your Name
9a6dd2934f update 2025-01-20 11:17:59 +01:00
Your Name
baaca785b1 update odometry. Changed measurements 2025-01-20 09:27:32 +01:00
7 changed files with 62 additions and 10 deletions

View File

@ -10,19 +10,19 @@ topics:
name : navigation
topic : nav_vel
timeout : 0.5
priority: 100
priority: 110
-
name : joystick
topic : joy_vel
timeout : 0.5
priority: 90
priority: 100
-
name : keyboard
topic : key_vel
timeout : 0.5
priority: 90
priority: 10
-
name : tablet
topic : tab_vel
timeout : 0.5
priority: 90
priority: 10

10
launch/joystick.yaml Normal file
View File

@ -0,0 +1,10 @@
priority: True
turbo:
linear_forward_min : 0.5
linear_forward_max : 1.0
linear_backward_min : 0.25
linear_backward_max : 0.5
angular_min : 0.7
angular_max : 1.2
steps : 4

View File

@ -48,5 +48,12 @@
<param name="global_frame_id" value="map"/>
<param name="tf_broadcast" value="true" /> -->
<!-- scan topic -->
<!-- <remap from="scan" to="scan_filtered"/> -->
<!-- remap cmd_vel -->
<remap from="cmd_vel" to="nav_vel"/>
<!-- remap odom -->
<remap from="odom" to="/robot_pose_ekf/odom_combined"/>
</node>
</launch>

View File

@ -0,0 +1,30 @@
<launch>
<param name="use_sim_time" value="false" />
<!--<include file="$(find segwayrmp)/launch/segwayrmp_configuration.launch" />-->
<!-- Run the map server -->
<!-- <node name="map_server" pkg="map_server" type="map_server" args="$(find segwayrmp)/maps/mymap.pgm my_map_resolution"/> -->
<!-- <node name="map_server" pkg="map_server" type="map_server" args="$(find cps_rmp220_support)/maps/map.yaml"/> -->
<!--move base-->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find segwayrmp)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find segwayrmp)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find segwayrmp)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find segwayrmp)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find segwayrmp)/param/base_local_planner_params.yaml" command="load" />
<!-- scan topic -->
<remap from="scan" to="scan_filtered"/>
<!-- remap cmd_vel -->
<remap from="cmd_vel" to="nav_vel"/>
<!-- remap odom -->
<remap from="odom" to="/robot_pose_ekf/odom_combined"/>
</node>
<!-- TF -->
<!-- <node pkg="tf" type="static_transform_publisher" name="base_to_laser" args="0.10 0.0 0.12 3.14 0.0 0.0 base_link laser 100"/>
static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period_in_ms -->
<!-- <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link" args="0 0 0.5 0 0 0 base_link base_footprint 50" /> -->
</launch>

View File

@ -15,6 +15,7 @@
<param name="scale_linear" value="0.5" /> <!-- Scale factor for linear velocity -->
<!-- Remap /cmd_vel to /joy_vel -->
<remap from="/cmd_vel" to="/joy_vel" />
<!-- <remap from="/cmd_vel" to="/joy_vel" /> -->
<remap from="/cmd_vel" to="/input_joy/cmd_vel" />
</node>
</launch>

View File

@ -5,9 +5,9 @@
<arg name="cmd_vel_out" default="twist_mux/cmd_vel"/>
<arg name="config_locks" default="$(find twist_mux)/config/twist_mux_locks.yaml"/>
<arg name="config_topics" default="$(find cps_rmp220_Support)/config/twist_mux_topics.yaml"/>
<arg name="config_topics" default="$(find cps_rmp220_support)/config/twist_mux_topics.yaml"/>
<arg name="config_joy" default="$(find twist_mux)/config/joystick.yaml"/>
<arg name="config_joy" default="$(find cps_rmp220_support)/config/joystick.yaml"/>
<node pkg="twist_mux" type="twist_mux" name="twist_mux" output="screen">
<remap from="cmd_vel_out" to="$(arg cmd_vel_out)"/>

View File

@ -1,5 +1,9 @@
#!/usr/bin/env python
"""
Node for pusblishing segway rmp 220 lite Odometry calculated from encoder ticks_fb
"""
import rospy
import tf
from nav_msgs.msg import Odometry
@ -12,9 +16,9 @@ class EncoderOdometry:
rospy.init_node("encoder_odom_publisher")
# Robot parameters (update these according to your robot)
self.wheel_radius = 0.202 # Wheel radius in meters
self.wheel_base = 0.392 # Distance between wheels (m)
self.ticks_per_revolution = 4096 # Encoder ticks per wheel revolution
self.wheel_radius = 0.125 #0.202 # Wheel radius in meters
self.wheel_base = 0.415 #0.392 # Distance between wheels (m)
self.ticks_per_revolution = 4096 # Encoder ticks per wheel revolution --> checked fine
# State variables
self.x = 0.0