Skip to content
Open
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
14 changes: 7 additions & 7 deletions odrive_demo_bringup/config/diffbot_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -40,18 +40,18 @@ diffbot_base_controller:
linear.x.has_velocity_limits: true
linear.x.has_acceleration_limits: true
linear.x.has_jerk_limits: false
linear.x.max_velocity: 1.0
linear.x.min_velocity: -1.0
linear.x.max_acceleration: 1.0
linear.x.max_velocity: 3.0
linear.x.min_velocity: -3.0
linear.x.max_acceleration: 3.0
linear.x.max_jerk: 0.0
linear.x.min_jerk: 0.0

angular.z.has_velocity_limits: true
angular.z.has_acceleration_limits: true
angular.z.has_jerk_limits: false
angular.z.max_velocity: 1.0
angular.z.min_velocity: -1.0
angular.z.max_acceleration: 1.0
angular.z.min_acceleration: -1.0
angular.z.max_velocity: 60.0
angular.z.min_velocity: -60.0
angular.z.max_acceleration: 60.0
angular.z.min_acceleration: -60.0
angular.z.max_jerk: 0.0
angular.z.min_jerk: 0.0
2 changes: 1 addition & 1 deletion odrive_demo_bringup/launch/odrive_diffbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -88,5 +88,5 @@ def generate_launch_description():
robot_state_pub_node,
joint_state_broadcaster_spawner,
robot_controller_spawner,
rviz_node
rviz_node,
])
4 changes: 2 additions & 2 deletions odrive_demo_description/urdf/odrive.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
<param name="serial_number">${serial_number}</param>
<param name="axis">0</param>
<param name="enable_watchdog">1</param>
<param name="watchdog_timeout">0.1</param>
<param name="watchdog_timeout">0.5</param>
</joint>
</xacro:if>

Expand All @@ -27,7 +27,7 @@
<param name="serial_number">${serial_number}</param>
<param name="axis">1</param>
<param name="enable_watchdog">1</param>
<param name="watchdog_timeout">0.1</param>
<param name="watchdog_timeout">0.5</param>
</joint>
</xacro:if>
</ros2_control>
Expand Down
4 changes: 2 additions & 2 deletions odrive_demo_description/urdf/odrive.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<joint name="joint0" type="continuous">
<parent link="world"/>
<child link="link0"/>
<axis xyz="0 0 1"/>
<axis xyz="1.0 0.0 0.0"/>
</joint>
</xacro:if>

Expand All @@ -22,7 +22,7 @@
<joint name="joint1" type="continuous">
<parent link="world"/>
<child link="link1"/>
<axis xyz="0 0 1"/>
<axis xyz="1.0 0.0 0.0"/>
</joint>
</xacro:if>

Expand Down
6 changes: 5 additions & 1 deletion odrive_hardware_interface/src/odrive_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -344,7 +344,11 @@ return_type ODriveHardwareInterface::write()
input_pos));

case integration_level_t::VELOCITY:
input_vel = hw_commands_velocities_[i] / 2 / M_PI;
if (i == 0) { // Only for joint1
input_vel = hw_commands_velocities_[i] / 2 / M_PI; // Negative velocity for joint1
} else {
input_vel = -hw_commands_velocities_[i] / 2 / M_PI; // Keep the same velocity for other joints
}
CHECK(odrive->write(
serial_numbers_[1][i], AXIS__CONTROLLER__INPUT_VEL + per_axis_offset * axes_[i],
input_vel));
Expand Down