void setCarCalHdl()

in ctrl_pkg/src/ctrl_node.cpp [332:348]


        void setCarCalHdl(const std::shared_ptr<rmw_request_id_t> request_header,
                          std::shared_ptr<deepracer_interfaces_pkg::srv::SetCalibrationSrv::Request> req,
                          std::shared_ptr<deepracer_interfaces_pkg::srv::SetCalibrationSrv::Response> res) {
            (void)request_header;
            if (activeState_ == stateList_.end()) {
                RCLCPP_ERROR(this->get_logger(), "No active state");
                res->error = 1;
                return;
            }
            std::vector<int> cal(ServoCalType::total);
            cal[ServoCalType::max] = req->max;
            cal[ServoCalType::mid] = req->mid;
            cal[ServoCalType::min] = req->min;
            cal[ServoCalType::polarity] = req->polarity;
            res->error = 0;
            activeState_->second->setCalibration(req->cal_type, cal);
        }