.. _program_listing_file__tmp_ws_src_smacc2_smacc2_sm_reference_library_sm_dance_bot_warehouse_include_sm_dance_bot_warehouse_states_s_pattern_states_sti_spattern_forward_1.hpp: Program Listing for File sti_spattern_forward_1.hpp =================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/smacc2/smacc2_sm_reference_library/sm_dance_bot_warehouse/include/sm_dance_bot_warehouse/states/s_pattern_states/sti_spattern_forward_1.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 RobosoftAI Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. /***************************************************************************************************************** * * Authors: Pablo Inigo Blasco, Brett Aldrich * ******************************************************************************************************************/ namespace sm_dance_bot_warehouse { namespace s_pattern_states { // STATE DECLARATION struct StiSPatternForward1 : public smacc2::SmaccState { using SmaccState::SmaccState; // TRANSITION TABLE typedef mpl::list< Transition, StiSPatternRotate2> // , // Transition, StiSPatternRotate1> >reactions; // STATE FUNCTIONS static void staticConfigure() { configure_orthogonal(); configure_orthogonal(); configure_orthogonal(); } void runtimeConfigure() { double extrasecurityMargin = 0.1; auto forwardBehavior = this->getClientBehavior(); cl_lidar::ClLidarSensor * lidarClient; this->requiresClient(lidarClient); auto lidarData = lidarClient->getComponent(); float fwdist = lidarData->getForwardDistance(25); if (!std::isnan(fwdist)) forwardBehavior->setForwardDistance( std::min(SS::pitch1_lenght_meters(), (float)(fwdist -extrasecurityMargin))); /*extra security margin for easy dynamic implementation of dynamic-smotion*/ else forwardBehavior->setForwardDistance( SS::pitch1_lenght_meters()); } }; } // namespace s_pattern_states } // namespace sm_dance_bot_warehouse