khi_robot_krnx_driver.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Kawasaki Heavy Industries, LTD.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef KHI_ROBOT_KRNX_DRIVER_H
36 #define KHI_ROBOT_KRNX_DRIVER_H
37 
38 #include <mutex>
39 #include <ros/ros.h>
40 #include <ros/console.h>
41 #include <khi_robot_driver.h>
42 #include <krnx.h>
43 
44 namespace khi_robot_control
45 {
46 #define KRNX_MSGSIZE 1024
47 #define KRNX_STDAXES 6
48 #define KRNX_MOTION_BUF 10
49 #define KRNX_PRINT_TH 1000
50 
51 struct KhiRobotKrnxRtcData
52 {
53  int sw;
54  int seq_no;
58 };
59 
60 class KhiRobotKrnxDriver : public KhiRobotDriver
61 {
62 public:
65  bool setState( const int& cont_no, const int& state );
66 
67  bool initialize( const int& cont_no, const double& period, KhiRobotData& data, const bool in_simulation = false ) override;
68  bool open( const int& cont_no, const std::string& ip_address, KhiRobotData& data ) override;
69  bool close( const int& cont_no ) override;
70  bool activate( const int& cont_no, KhiRobotData& data ) override;
71  bool hold( const int& cont_no, const KhiRobotData& data ) override;
72  bool deactivate( const int& cont_no, const KhiRobotData& data ) override;
73  bool readData( const int& cont_no, KhiRobotData& data ) override;
74  bool writeData( const int& cont_no, const KhiRobotData& data ) override;
75  bool updateState( const int& cont_no, const KhiRobotData& data ) override;
76  bool getPeriodDiff( const int& cont_no, double& diff ) override;
77  bool commandHandler( khi_robot_msgs::KhiRobotCmd::Request& req, khi_robot_msgs::KhiRobotCmd::Response& res ) override;
78 
79 private:
80  /* general */
82  char msg_buf[KRNX_MSGSIZE];
84  std::mutex mutex_state[KRNX_MAX_CONTROLLER];
85 
86  /* RTC */
88 
89  bool getCurMotionData( const int& cont_no, const int& robot_no, TKrnxCurMotionData* p_motion_data );
90  int execAsMonCmd( const int& cont_no, const char* cmd, char* buffer, int buffer_sz, int* as_err_code );
91  bool retKrnxRes( const int& cont_no, const std::string& name, const int& ret, const bool error = true );
92  bool conditionCheck( const int& cont_no, const KhiRobotData& data );
93  bool setRobotDataHome( const int& cont_no, KhiRobotData& data );
94  std::vector<std::string> splitString( const std::string& str, const char& del );
95  bool loadDriverParam( const int& cont_no, KhiRobotData& data );
96  bool loadRtcProg( const int& cont_no, const std::string& name );
97  bool syncRtcPos( const int& cont_no, KhiRobotData& data );
98 };
99 
100 } // namespace
101 
102 #endif // KHI_ROBOT_KRNX_DRIVER_H
khi_robot_control::KhiRobotKrnxDriver::open
bool open(const int &cont_no, const std::string &ip_address, KhiRobotData &data) override
Definition: khi_robot_krnx_driver.cpp:213
KRNX_MAX_CONTROLLER
#define KRNX_MAX_CONTROLLER
Definition: krnx.h:59
khi_robot_control::KhiRobotKrnxDriver::getCurMotionData
bool getCurMotionData(const int &cont_no, const int &robot_no, TKrnxCurMotionData *p_motion_data)
Definition: khi_robot_krnx_driver.cpp:637
khi_robot_control::KhiRobotKrnxDriver::activate
bool activate(const int &cont_no, KhiRobotData &data) override
Definition: khi_robot_krnx_driver.cpp:283
ros.h
khi_robot_control::KhiRobotKrnxDriver::loadDriverParam
bool loadDriverParam(const int &cont_no, KhiRobotData &data)
Definition: khi_robot_krnx_driver.cpp:481
khi_robot_control::KhiRobotKrnxRtcData::old_comp
float old_comp[KRNX_MAX_ROBOT][KRNX_MAXAXES]
Definition: khi_robot_krnx_driver.h:88
khi_robot_control::KhiRobotKrnxDriver::readData
bool readData(const int &cont_no, KhiRobotData &data) override
Definition: khi_robot_krnx_driver.cpp:564
khi_robot_control::KhiRobotDriver::in_simulation
bool in_simulation
Definition: khi_robot_driver.h:337
khi_robot_control::KhiRobotKrnxDriver::deactivate
bool deactivate(const int &cont_no, const KhiRobotData &data) override
Definition: khi_robot_krnx_driver.cpp:443
KRNX_MSGSIZE
#define KRNX_MSGSIZE
Definition: khi_robot_krnx_driver.h:78
khi_robot_control::KhiRobotKrnxDriver::conditionCheck
bool conditionCheck(const int &cont_no, const KhiRobotData &data)
Definition: khi_robot_krnx_driver.cpp:147
khi_robot_control::KhiRobotKrnxRtcData
Definition: khi_robot_krnx_driver.h:83
khi_robot_control::KhiRobotKrnxDriver::sw_dblrefflt
int sw_dblrefflt[KRNX_MAX_CONTROLLER]
Definition: khi_robot_krnx_driver.h:115
khi_robot_control::KhiRobotKrnxDriver::commandHandler
bool commandHandler(khi_robot_msgs::KhiRobotCmd::Request &req, khi_robot_msgs::KhiRobotCmd::Response &res) override
Definition: khi_robot_krnx_driver.cpp:958
khi_robot_control::KhiRobotKrnxDriver::setState
bool setState(const int &cont_no, const int &state)
Definition: khi_robot_krnx_driver.cpp:106
console.h
khi_robot_control::KhiRobotKrnxDriver::setRobotDataHome
bool setRobotDataHome(const int &cont_no, KhiRobotData &data)
Definition: khi_robot_krnx_driver.cpp:646
TKrnxCurMotionData
Definition: krnx.h:563
khi_robot_control::KhiRobotKrnxDriver::rtc_data
KhiRobotKrnxRtcData rtc_data[KRNX_MAX_CONTROLLER]
Definition: khi_robot_krnx_driver.h:119
khi_robot_control::KhiRobotKrnxRtcData::sw
int sw
Definition: khi_robot_krnx_driver.h:85
khi_robot_control::KhiRobotKrnxDriver::syncRtcPos
bool syncRtcPos(const int &cont_no, KhiRobotData &data)
Definition: khi_robot_krnx_driver.cpp:937
khi_robot_driver.h
khi_robot_control::KhiRobotKrnxDriver::getPeriodDiff
bool getPeriodDiff(const int &cont_no, double &diff) override
Definition: khi_robot_krnx_driver.cpp:812
khi_robot_control::KhiRobotKrnxDriver::~KhiRobotKrnxDriver
~KhiRobotKrnxDriver()
Definition: khi_robot_krnx_driver.cpp:91
khi_robot_control::KhiRobotKrnxDriver::updateState
bool updateState(const int &cont_no, const KhiRobotData &data) override
Definition: khi_robot_krnx_driver.cpp:763
khi_robot_control::KhiRobotKrnxDriver::initialize
bool initialize(const int &cont_no, const double &period, KhiRobotData &data, const bool in_simulation=false) override
Definition: khi_robot_krnx_driver.cpp:198
khi_robot_control::KhiRobotKrnxDriver::hold
bool hold(const int &cont_no, const KhiRobotData &data) override
Definition: khi_robot_krnx_driver.cpp:427
khi_robot_control::KhiRobotKrnxDriver::KhiRobotKrnxDriver
KhiRobotKrnxDriver()
Definition: khi_robot_krnx_driver.cpp:81
khi_robot_control::KhiRobotKrnxDriver::cmd_buf
char cmd_buf[KRNX_MSGSIZE]
Definition: khi_robot_krnx_driver.h:113
khi_robot_control::KhiRobotData
Definition: khi_robot_driver.h:92
krnx.h
khi_robot_control
Definition: khi_robot_client.h:42
khi_robot_control::KhiRobotKrnxDriver::writeData
bool writeData(const int &cont_no, const KhiRobotData &data) override
Definition: khi_robot_krnx_driver.cpp:685
KRNX_MAX_ROBOT
#define KRNX_MAX_ROBOT
Definition: krnx.h:61
khi_robot_control::KhiRobotKrnxRtcData::status
int status[KRNX_MAX_ROBOT][KRNX_MAXAXES]
Definition: khi_robot_krnx_driver.h:89
khi_robot_control::KhiRobotKrnxDriver::mutex_state
std::mutex mutex_state[KRNX_MAX_CONTROLLER]
Definition: khi_robot_krnx_driver.h:116
khi_robot_control::KhiRobotKrnxRtcData::seq_no
int seq_no
Definition: khi_robot_krnx_driver.h:86
khi_robot_control::KhiRobotKrnxDriver::msg_buf
char msg_buf[KRNX_MSGSIZE]
Definition: khi_robot_krnx_driver.h:114
KRNX_MAXAXES
#define KRNX_MAXAXES
Definition: krnx.h:66
khi_robot_control::KhiRobotKrnxRtcData::comp
float comp[KRNX_MAX_ROBOT][KRNX_MAXAXES]
Definition: khi_robot_krnx_driver.h:87
khi_robot_control::KhiRobotKrnxDriver::splitString
std::vector< std::string > splitString(const std::string &str, const char &del)
Definition: khi_robot_krnx_driver.cpp:850
khi_robot_control::KhiRobotKrnxDriver::close
bool close(const int &cont_no) override
Definition: khi_robot_krnx_driver.cpp:253
khi_robot_control::KhiRobotKrnxDriver::loadRtcProg
bool loadRtcProg(const int &cont_no, const std::string &name)
Definition: khi_robot_krnx_driver.cpp:868
khi_robot_control::KhiRobotKrnxDriver::retKrnxRes
bool retKrnxRes(const int &cont_no, const std::string &name, const int &ret, const bool error=true)
Definition: khi_robot_krnx_driver.cpp:132
khi_robot_control::KhiRobotKrnxDriver::execAsMonCmd
int execAsMonCmd(const int &cont_no, const char *cmd, char *buffer, int buffer_sz, int *as_err_code)
Definition: khi_robot_krnx_driver.cpp:115


khi_robot_control
Author(s): nakamichi_d
autogenerated on Sat Oct 21 2023 02:54:50