-
Notifications
You must be signed in to change notification settings - Fork 45
fixed closed loop odom initialization #83
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
base: jazzy
Are you sure you want to change the base?
Changes from 1 commit
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
@@ -44,6 +44,7 @@ hardware_interface::CallbackReturn TurtleBot3ManipulationSystemHardware::on_init | |||||||||||||||||||||||||||||
usb_port_ = info_.hardware_parameters["opencr_usb_port"]; | ||||||||||||||||||||||||||||||
baud_rate_ = stoi(info_.hardware_parameters["opencr_baud_rate"]); | ||||||||||||||||||||||||||||||
heartbeat_ = 0; | ||||||||||||||||||||||||||||||
init_wheel_offsets_ = true; | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
joints_acceleration_[0] = stoi(info_.hardware_parameters["dxl_joints_profile_acceleration"]); | ||||||||||||||||||||||||||||||
joints_acceleration_[1] = stoi(info_.hardware_parameters["dxl_joints_profile_acceleration"]); | ||||||||||||||||||||||||||||||
|
@@ -225,10 +226,10 @@ hardware_interface::return_type TurtleBot3ManipulationSystemHardware::read( | |||||||||||||||||||||||||||||
RCLCPP_WARN(logger, "Failed to read all control table"); | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
dxl_positions_[0] = opencr_->get_wheel_positions()[opencr::wheels::LEFT]; | ||||||||||||||||||||||||||||||
dxl_positions_[0] = opencr_->get_wheel_positions()[opencr::wheels::LEFT] - dxl_wheel_offsets_[opencr::wheels::LEFT]; | ||||||||||||||||||||||||||||||
dxl_velocities_[0] = opencr_->get_wheel_velocities()[opencr::wheels::LEFT]; | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
dxl_positions_[1] = opencr_->get_wheel_positions()[opencr::wheels::RIGHT]; | ||||||||||||||||||||||||||||||
dxl_positions_[1] = opencr_->get_wheel_positions()[opencr::wheels::RIGHT] - dxl_wheel_offsets_[opencr::wheels::RIGHT]; | ||||||||||||||||||||||||||||||
Comment on lines
+229
to
+232
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Consider adding a check to ensure that
Suggested change
|
||||||||||||||||||||||||||||||
dxl_velocities_[1] = opencr_->get_wheel_velocities()[opencr::wheels::RIGHT]; | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
dxl_positions_[2] = opencr_->get_joint_positions()[opencr::joints::JOINT1]; | ||||||||||||||||||||||||||||||
|
@@ -287,6 +288,12 @@ hardware_interface::return_type TurtleBot3ManipulationSystemHardware::write( | |||||||||||||||||||||||||||||
if (opencr_->set_gripper_position(dxl_gripper_commands_[0]) == false) { | ||||||||||||||||||||||||||||||
RCLCPP_ERROR(logger, "Can't control gripper"); | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
if (init_wheel_offsets_){ | ||||||||||||||||||||||||||||||
dxl_wheel_offsets_ = opencr_->get_wheel_positions(); // First time returns all zeros | ||||||||||||||||||||||||||||||
dxl_wheel_offsets_ = opencr_->get_wheel_positions(); // Second time returns the offsets | ||||||||||||||||||||||||||||||
init_wheel_offsets_ = false; | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
Comment on lines
+292
to
+296
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The double read of Could you elaborate on why the first call returns zeros? Is this intentional, or a side effect of the underlying implementation?
Suggested change
|
||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
return hardware_interface::return_type::OK; | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Enabling
use_stamped_vel
is a good change for ensuring proper time synchronization. However, it's worth noting that this requires thecmd_vel
messages to be stamped with a timestamp. Ensure that the upstream nodes publishingcmd_vel
are configured to do so.