Skip to content

Commit

Permalink
update for spec 2.0.x
Browse files Browse the repository at this point in the history
  • Loading branch information
yconst committed Apr 23, 2024
1 parent 1604759 commit 3c1ef04
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 122 deletions.
12 changes: 11 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,14 +130,24 @@ include_directories(
set(TINYMOVR_SOURCES
src/tinymovr/can.cpp
src/tinymovr/comms.cpp
src/tinymovr/commutation_sensor.cpp
src/tinymovr/controller.cpp
src/tinymovr/current.cpp
src/tinymovr/encoder.cpp
src/tinymovr/external_spi.cpp
src/tinymovr/hall.cpp
src/tinymovr/homing.cpp
src/tinymovr/motor.cpp
src/tinymovr/onboard.cpp
src/tinymovr/position_sensor.cpp
src/tinymovr/position.cpp
src/tinymovr/scheduler.cpp
src/tinymovr/select.cpp
src/tinymovr/sensors.cpp
src/tinymovr/setup.cpp
src/tinymovr/stall_detect.cpp
src/tinymovr/tinymovr.cpp
src/tinymovr/traj_planner.cpp
src/tinymovr/user_frame.cpp
src/tinymovr/velocity.cpp
src/tinymovr/voltage.cpp
src/tinymovr/watchdog.cpp
Expand Down
28 changes: 0 additions & 28 deletions include/tinymovr/encoder.hpp

This file was deleted.

90 changes: 0 additions & 90 deletions src/tinymovr/encoder.cpp

This file was deleted.

8 changes: 5 additions & 3 deletions src/tm_joint_iface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,9 @@ bool TinymovrJoint::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh)
ROS_DEBUG("Asserting calibrated");
for (int i=0; i<num_joints; i++)
{
ROS_ASSERT((servos[i].encoder.get_calibrated() == true) && (servos[i].motor.get_calibrated() == true));
ROS_ASSERT((servos[i].sensors.select.commutation_sensor.get_calibrated() == true)
&& (servos[i].sensors.select.position_sensor.get_calibrated() == true)
&& (servos[i].motor.get_calibrated() == true));
ROS_DEBUG("%s ok", joint_name[i].c_str());
}

Expand Down Expand Up @@ -327,8 +329,8 @@ void TinymovrJoint::read(const ros::Time& time, const ros::Duration& period)
for (int i=0; i<servos.size(); i++)
{
const double ticks_to_rads = 1.0/rads_to_ticks[i];
joint_position_state[i] = servos[i].encoder.get_position_estimate() * ticks_to_rads;
joint_velocity_state[i] = servos[i].encoder.get_velocity_estimate() * ticks_to_rads;
joint_position_state[i] = servos[i].sensors.user_frame.get_position_estimate() * ticks_to_rads;
joint_velocity_state[i] = servos[i].sensors.user_frame.get_velocity_estimate() * ticks_to_rads;
joint_effort_state[i] = servos[i].controller.current.get_Iq_estimate();
}
}
Expand Down

0 comments on commit 3c1ef04

Please sign in to comment.