Skip to content

Commit 4a3f8ea

Browse files
committed
style: fix linting and format
1 parent 5858f6f commit 4a3f8ea

File tree

4 files changed

+7
-6
lines changed

4 files changed

+7
-6
lines changed

extensions/rcs_robotics_library/src/rcs_robotics_library/__init__.pyi

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,4 @@ from __future__ import annotations
22

33
from rcs_robotics_library._core import rl
44

5-
from . import _core
6-
75
__all__: list = ["rl"]

extensions/rcs_so101/src/rcs_so101/creators.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,6 @@
1414
from rcs_so101 import SO101IK
1515
from rcs_so101.hw import SO101, SO101Config, SO101Gripper
1616

17-
import rcs
18-
1917
logger = logging.getLogger(__name__)
2018
logger.setLevel(logging.INFO)
2119

src/sim/SimRobot.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -131,6 +131,10 @@ void SimRobot::set_joint_position(const common::VectorXd& q) {
131131
}
132132

133133
common::VectorXd SimRobot::get_joint_position() {
134+
return m_get_joint_position();
135+
}
136+
137+
common::VectorXd SimRobot::m_get_joint_position() {
134138
common::VectorXd q(std::size(this->cfg.joints));
135139
for (size_t i = 0; i < std::size(this->cfg.joints); ++i) {
136140
q[i] = this->sim->d->qpos[this->sim->m->jnt_qposadr[this->ids.joints[i]]];
@@ -195,8 +199,8 @@ void SimRobot::m_reset() {
195199
this->state = SimRobotState();
196200
this->set_joints_hard(
197201
common::robots_meta_config.at(this->cfg.robot_type).q_home);
198-
this->state.previous_angles = this->get_joint_position();
199-
this->state.target_angles = this->get_joint_position();
202+
this->state.previous_angles = this->m_get_joint_position();
203+
this->state.target_angles = this->m_get_joint_position();
200204
this->state.is_arrived = true;
201205
this->state.is_moving = false;
202206
}

src/sim/SimRobot.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,7 @@ class SimRobot : public common::Robot {
9696
void init_ids();
9797
void construct();
9898
void m_reset();
99+
common::VectorXd m_get_joint_position();
99100
};
100101
} // namespace sim
101102
} // namespace rcs

0 commit comments

Comments
 (0)