khi_robot_client.cpp
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 #include <stdio.h>
36 #include <boost/thread/thread.hpp>
37 #include <khi_robot_client.h>
38 #include <khi_robot_krnx_driver.h>
39 
40 namespace khi_robot_control
41 {
42 void KhiCommandService( KhiRobotDriver* driver )
43 {
44  if ( driver == NULL ) return;
45 
46  ROS_INFO( "[KhiRobotCommandService] Start" );
47 
48  ros::AsyncSpinner spinner(boost::thread::hardware_concurrency()-1);
49  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
50  ros::ServiceServer service = node->advertiseService( "khi_robot_command_service", &KhiRobotDriver::commandHandler, driver );
51  spinner.start();
53 }
54 
55 bool KhiRobotClient::open( const std::string& ip, const double& period, KhiRobotData& data, const bool in_simulation )
56 {
57  cont_no = 0;
58 
59  /* select driver */
60  driver = new KhiRobotKrnxDriver();
61  if ( !driver->initialize( cont_no, period, data, in_simulation ) ) { return false; }
62 
63  /* open */
64  if ( !driver->open( cont_no, ip, data ) ) { return false; }
65 
67 
68  return true;
69 }
70 
71 bool KhiRobotClient::activate( KhiRobotData& data )
72 {
73  if ( driver == NULL ) { return false; }
74 
75  return driver->activate( cont_no, data );
76 }
77 
78 bool KhiRobotClient::hold( const KhiRobotData& data )
79 {
80  if ( driver == NULL ) { return false; }
81 
82  return driver->hold( cont_no, data );
83 }
84 
85 void KhiRobotClient::deactivate( const KhiRobotData& data )
86 {
87  if ( driver == NULL ) { return; }
88 
89  driver->deactivate( cont_no, data );
90 }
91 
93 {
94  if ( driver == NULL ) { return; }
95 
96  driver->close( cont_no );
97  delete driver;
98 }
99 
100 void KhiRobotClient::write( const KhiRobotData& data )
101 {
102  if ( driver == NULL ) { return; }
103 
104  driver->writeData( cont_no, data );
105 }
106 
108 {
109  if ( driver == NULL ) { return; }
110 
111  driver->readData( cont_no, data );
112 }
113 
114 int KhiRobotClient::updateState( const KhiRobotData& data )
115 {
116  if ( driver == NULL ) { return NOT_REGISTERED; }
117 
118  return driver->updateState( cont_no, data );
119 }
120 
122 {
123  if ( driver == NULL ) { return NONE; }
124 
125  return driver->getStateTrigger( cont_no );
126 }
127 
128 bool KhiRobotClient::getPeriodDiff( double& diff )
129 {
130  if ( driver == NULL ) { return false; }
131 
132  return driver->getPeriodDiff( cont_no, diff );
133 }
134 
136 {
137  if ( driver == NULL ) { return; }
138 
139  boost::thread thread_srv( KhiCommandService, driver );
140 }
141 
142 } // end of khi_robot_control namespace
khi_robot_control::KhiRobotClient::startCommandService
void startCommandService()
Definition: khi_robot_client.cpp:167
khi_robot_control::KhiRobotDriver::open
virtual bool open(const int &cont_no, const std::string &ip_address, KhiRobotData &data)=0
khi_robot_control::KhiRobotDriver::initialize
virtual bool initialize(const int &cont_no, const double &period, KhiRobotData &data, const bool in_simulation=false)=0
khi_robot_control::NOT_REGISTERED
@ NOT_REGISTERED
Definition: khi_robot_driver.h:120
khi_robot_control::KhiRobotClient::driver
KhiRobotDriver * driver
Definition: khi_robot_client.h:131
khi_robot_control::KhiRobotDriver::activate
virtual bool activate(const int &cont_no, KhiRobotData &data)=0
boost::shared_ptr< NodeHandle >
khi_robot_control::KhiRobotDriver::close
virtual bool close(const int &cont_no)=0
khi_robot_control::KhiRobotClient::close
void close()
Definition: khi_robot_client.cpp:124
ros::AsyncSpinner
khi_robot_control::KhiRobotDriver::hold
virtual bool hold(const int &cont_no, const KhiRobotData &data)=0
khi_robot_control::KhiRobotClient::deactivate
void deactivate(const KhiRobotData &data)
Definition: khi_robot_client.cpp:117
khi_robot_control::KhiRobotDriver::commandHandler
virtual bool commandHandler(khi_robot_msgs::KhiRobotCmd::Request &req, khi_robot_msgs::KhiRobotCmd::Response &res)=0
khi_robot_krnx_driver.h
khi_robot_control::KhiRobotDriver::writeData
virtual bool writeData(const int &cont_no, const KhiRobotData &data)=0
ros::ServiceServer
spinner
void spinner()
khi_robot_control::KhiRobotDriver::deactivate
virtual bool deactivate(const int &cont_no, const KhiRobotData &data)=0
khi_robot_control::KhiRobotClient::read
void read(KhiRobotData &data)
Definition: khi_robot_client.cpp:139
khi_robot_control::KhiRobotDriver::getPeriodDiff
virtual bool getPeriodDiff(const int &cont_no, double &diff)=0
khi_robot_control::KhiRobotClient::cont_no
int cont_no
Definition: khi_robot_client.h:130
khi_robot_control::KhiRobotClient::activate
bool activate(KhiRobotData &data)
Definition: khi_robot_client.cpp:103
khi_robot_control::KhiRobotDriver::getStateTrigger
int getStateTrigger(const int &cont_no)
Definition: khi_robot_driver.h:224
khi_robot_control::KhiRobotClient::open
bool open(const std::string &ip, const double &period, KhiRobotData &data, const bool in_simulation=false)
Definition: khi_robot_client.cpp:87
khi_robot_control::KhiRobotClient::hold
bool hold(const KhiRobotData &data)
Definition: khi_robot_client.cpp:110
khi_robot_control::KhiRobotClient::getStateTrigger
int getStateTrigger()
Definition: khi_robot_client.cpp:153
khi_robot_control::KhiRobotData
Definition: khi_robot_driver.h:92
khi_robot_control::KhiRobotClient::updateState
int updateState(const KhiRobotData &data)
Definition: khi_robot_client.cpp:146
khi_robot_control::KhiCommandService
void KhiCommandService(KhiRobotDriver *driver)
Definition: khi_robot_client.cpp:74
khi_robot_control
Definition: khi_robot_client.h:42
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
khi_robot_control::NONE
@ NONE
Definition: khi_robot_driver.h:141
khi_robot_client.h
khi_robot_control::KhiRobotDriver::readData
virtual bool readData(const int &cont_no, KhiRobotData &data)=0
khi_robot_control::KhiRobotClient::write
void write(const KhiRobotData &data)
Definition: khi_robot_client.cpp:132
ROS_INFO
#define ROS_INFO(...)
khi_robot_control::KhiRobotDriver::updateState
virtual bool updateState(const int &cont_no, const KhiRobotData &data)=0
khi_robot_control::KhiRobotClient::getPeriodDiff
bool getPeriodDiff(double &diff)
Definition: khi_robot_client.cpp:160


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