m12watanabe1a 2023-11-24
Optimize calculations
@74bfef339dad5fc0807a5c09d96c517e26f2fd96
p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
--- p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
+++ p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
@@ -32,7 +32,6 @@
   using Joy = sensor_msgs::msg::Joy;
 
 private:
-  float speed_factor_ = 1.0;
   double linear_max_speed_, angular_max_speed_;
 
   p9n_interface::HW_TYPE hw_type_;
p9n_node/src/teleop_twist_joy_node.cpp
--- p9n_node/src/teleop_twist_joy_node.cpp
+++ p9n_node/src/teleop_twist_joy_node.cpp
@@ -64,15 +64,14 @@
   this->timer_watchdog_->reset();
   this->p9n_if_->setJoyMsg(joy_msg);
 
-  const double PI = 3.14159;
   static bool stopped = true;
   if (this->p9n_if_->isTiltedStickL()) {
     auto twist_msg = std::make_unique<Twist>();
     twist_msg->linear.set__x(this->linear_max_speed_ * this->p9n_if_->tiltedStickLY());
 
-    if (this->p9n_if_->tiltedStickLY() > sin(PI / 8)) {
+    if (this->p9n_if_->tiltedStickLY() > sin(M_PI * 0.125)) {
       twist_msg->angular.set__z(this->angular_max_speed_ * this->p9n_if_->tiltedStickLX());
-    } else if (this->p9n_if_->tiltedStickLY() < sin(-PI / 8)) {
+    } else if (this->p9n_if_->tiltedStickLY() < sin(-M_PI * 0.125)) {
       twist_msg->angular.set__z(-this->angular_max_speed_ * this->p9n_if_->tiltedStickLX());
     } else {
       twist_msg->linear.set__x(0.0);
Add a comment
List