Skip to content

Commit

Permalink
feat: use const for path variable
Browse files Browse the repository at this point in the history
  • Loading branch information
borednuna committed Jun 6, 2024
1 parent 07e9af8 commit 9df35fd
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 10 deletions.
8 changes: 4 additions & 4 deletions include/tachimawari/joint/tf2/frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,9 @@ class Frame
const double translation_z, const double const_roll, const double const_pitch,
const double const_yaw);

void update_quaternion(std::vector<Joint> current_joints);
void update_quaternion(keisan::Angle<double> imu_yaw);
geometry_msgs::msg::TransformStamped get_transform_stamped(rclcpp::Time time_stamp);
void update_quaternion(const std::vector<Joint> & current_joints);
void update_quaternion(const keisan::Angle<double> & imu_yaw);
geometry_msgs::msg::TransformStamped get_transform_stamped(const rclcpp::Time & time_stamp);

uint8_t id;

Expand All @@ -70,7 +70,7 @@ class Frame
YAW,
};

double get_joint_angle(uint8_t quaternion_axis, std::vector<Joint> current_joints);
double get_joint_angle(const uint8_t & quaternion_axis, const std::vector<Joint> & current_joints);
};
} // namespace tachimawari::joint

Expand Down
2 changes: 1 addition & 1 deletion include/tachimawari/joint/tf2/tf2_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class Tf2Manager
explicit Tf2Manager();

bool load_configuration(const std::string & path);
void update(std::vector<Joint> current_joints, keisan::Angle<double> imu_yaw);
void update(const std::vector<Joint> & current_joints, const keisan::Angle<double> & imu_yaw);
std::vector<Frame> get_frames() { return frames; }

private:
Expand Down
8 changes: 4 additions & 4 deletions src/tachimawari/joint/tf2/frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ Frame::Frame(
{
}

geometry_msgs::msg::TransformStamped Frame::get_transform_stamped(rclcpp::Time time_stamp)
geometry_msgs::msg::TransformStamped Frame::get_transform_stamped(const rclcpp::Time & time_stamp)
{
auto map_string_name = FrameId::frame_id_string.find(id);
std::string frame_name = map_string_name->second;
Expand All @@ -72,7 +72,7 @@ geometry_msgs::msg::TransformStamped Frame::get_transform_stamped(rclcpp::Time t
return t;
}

void Frame::update_quaternion(std::vector<Joint> current_joints)
void Frame::update_quaternion(const std::vector<Joint> & current_joints)
{
double roll_deg = get_joint_angle(ROLL, current_joints) + const_roll;
double pitch_deg = get_joint_angle(PITCH, current_joints) + const_pitch;
Expand All @@ -91,7 +91,7 @@ void Frame::update_quaternion(std::vector<Joint> current_joints)
quaternion_w = q.w();
}

void Frame::update_quaternion(keisan::Angle<double> imu_yaw)
void Frame::update_quaternion(const keisan::Angle<double> & imu_yaw)
{
tf2::Quaternion q;
q.setRPY(0, 0, imu_yaw.radian());
Expand All @@ -102,7 +102,7 @@ void Frame::update_quaternion(keisan::Angle<double> imu_yaw)
quaternion_w = q.w();
}

double Frame::get_joint_angle(uint8_t quaternion_axis, std::vector<Joint> current_joints)
double Frame::get_joint_angle(const uint8_t & quaternion_axis, const std::vector<Joint> & current_joints)
{
auto map = FrameId::frame_joint_map.find(id);
std::vector<uint8_t> frame_joints = map->second;
Expand Down
2 changes: 1 addition & 1 deletion src/tachimawari/joint/tf2/tf2_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ bool Tf2Manager::load_configuration(const std::string & path)
return true;
}

void Tf2Manager::update(std::vector<Joint> current_joints, keisan::Angle<double> imu_yaw)
void Tf2Manager::update(const std::vector<Joint> & current_joints, const keisan::Angle<double> & imu_yaw)
{
for (auto & item : frames) {
if (item.id == FrameId::ODOM) {
Expand Down

0 comments on commit 9df35fd

Please sign in to comment.