Skip to content

Commit

Permalink
Merge branch 'mirte-master' of https://github.com/arendjan/mirte-ros-…
Browse files Browse the repository at this point in the history
…packages into mirte-master
  • Loading branch information
ArendJan committed Feb 9, 2024
2 parents 0920c4c + bfb2155 commit 7011d85
Show file tree
Hide file tree
Showing 5 changed files with 100 additions and 23 deletions.
14 changes: 7 additions & 7 deletions mirte_control/config/control_master.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ mobile_base_controller:
# Override URDF look-up for wheel separation since the parent link is not the base_link.
wheel_separation_x: 0.638
wheel_separation_y: 0.551
wheel_radius: 0.165
wheel_radius: 0.08
# Odometry fused with IMU is published by robot_localization, so
# no need to publish a TF based on encoders alone.
enable_odom_tf: true
Expand All @@ -29,20 +29,20 @@ mobile_base_controller:
# Whenever a min_* is unspecified, default to -max_*
linear:
x:
has_velocity_limits : true
has_velocity_limits : false
max_velocity : 1.1 # m/s
has_acceleration_limits: true
has_acceleration_limits: false
max_acceleration : 2.5 # m/s^2
y:
has_velocity_limits : true
has_velocity_limits : false
max_velocity : 1.1 # m/s
has_acceleration_limits: true
has_acceleration_limits: false
max_acceleration : 2.5 # m/s^2
angular:
z:
has_velocity_limits : true
has_velocity_limits : false
max_velocity : 2.0 # rad/s
has_acceleration_limits: true
has_acceleration_limits: false
max_acceleration : 1.0 # rad/s^2

# ekf_localization:
Expand Down
76 changes: 62 additions & 14 deletions mirte_telemetrix/config/mirte_master_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,23 +12,19 @@ modules:
frequency: 1500
motors:
left_front:
pin_A: 8
pin_B: 9
pin_A: 0
pin_B: 1
left_rear:
pin_A: 10
pin_B: 11
pin_A: 3
pin_B: 2
right_front:
pin_A: 12
pin_B: 13
pin_A: 5
pin_B: 4
right_rear:
pin_A: 14
pin_B: 15
servos:
servo1:
pin: 1
servo_controller:
device: mirte
type: Hiwonder_Servo
pin_A: 7
pin_B: 6

type: Hiwonder_Servo
uart: 0
rx_pin: 0
tx_pin: 1
Expand All @@ -41,3 +37,55 @@ modules:
id: 4
min_angle: 800
max_angle: 4000
encoder:
left_front:
name: left_front
device: mirte
pins:
A: 21
B: 20
left_rear:
name: left_rear
device: mirte
pins:
A: 17
B: 16
right_front:
name: right_front
device: mirte
pins:
A: 18
B: 19
right_rear:
name: right_rear
device: mirte
pins:
A: 15
B: 14

# servos:
# servo1:
# pin: 1
# servo_controller:
# device: mirte
# type: Hiwonder_Servo
# uart: 0
# rx_pin: 0
# tx_pin: 1
# servos:
# servoH1:
# id: 3
# min_angle: 9000
# max_angle: 14000
# servoH2:
# id: 4
# min_angle: 800
# max_angle: 4000
# power_watcher:
# device: mirte
# type: INA226
# connector: I2C1
# id: 0x41
# min_voltage: 11
# max_current: 1
# max_voltage: 15
12 changes: 12 additions & 0 deletions mirte_teleop/config/ps3-holonomic.config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
axis_linear:
x: 1
y: 0
scale_linear:
x: 2
y: 2
axis_angular:
yaw: 3
scale_angular:
yaw: 2
enable_button: 0
enable_turbo_button: 8
17 changes: 17 additions & 0 deletions mirte_teleop/launch/teleop_holo_joy.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<launch>
<node name="joy"
pkg="joy"
type="joy_node" output="screen">
<param name="dev" value="/dev/input/js0"/>
</node>
<group ns="teleop_twist_joy">
<rosparam command="load" file="$(find mirte_teleop)/config/ps3-holonomic.config.yaml"/>
</group>
<node name="teleop_twist_joy"
pkg="teleop_twist_joy"
type="teleop_node" output="screen">
<!-- <param name="scale_linear" value="2"/>
<param name="scale_angular" value="2"/> -->
<remap from="/cmd_vel" to="/mobile_base_controller/cmd_vel"/>
</node>
</launch>
4 changes: 2 additions & 2 deletions mirte_teleop/launch/teleopkey.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
<node name="teleop_twist_keyboard"
pkg="teleop_twist_keyboard"
type="teleop_twist_keyboard.py" output="screen">
<param name="speed" value="0.04"/>
<param name="turn" value="0.55"/>
<param name="speed" value="2"/>
<param name="turn" value="2"/>
<remap from="/cmd_vel" to="/mobile_base_controller/cmd_vel"/>
</node>

Expand Down

0 comments on commit 7011d85

Please sign in to comment.