force_torque_sensor_config.cpp
Go to the documentation of this file.
1 /****************************************************************
2  *
3  * Copyright 2016 Intelligent Industrial Robotics (IIROB) Group,
4  * Institute for Anthropomatics and Robotics (IAR) -
5  * Intelligent Process Control and Robotics (IPR),
6  * Karlsruhe Institute of Technology
7  *
8  * Author: Denis Štogl, email: denis.stogl@kit.edu
9  *
10  * Date of creation: 2014-2016
11  *
12  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
13  *
14  * Redistribution and use in source and binary forms,
15  * with or without modification, are permitted provided
16  * that the following conditions are met:
17  *
18  * * Redistributions of source code must retain the above copyright
19  * notice, this list of conditions and the following disclaimer.
20  * * Redistributions in binary form must reproduce the above copyright
21  * notice, this list of conditions and the following disclaimer in the
22  * documentation and/or other materials provided with the distribution.
23  * * Neither the name of the copyright holder nor the names of its
24  * contributors may be used to endorse or promote products derived from
25  * this software without specific prior written permission.
26  *
27  * This program is free software: you can redistribute it and/or modify
28  * it under the terms of the GNU Lesser General Public License as published by
29  * the Free Software Foundation, either version 3 of the License, or
30  * (at your option) any later version.
31  *
32  * This package is distributed in the hope that it will be useful,
33  * but WITHOUT ANY WARRANTY; without even the implied warranty of
34  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
35  * GNU Lesser General Public License for more details.
36  *
37  * You should have received a copy of the GNU Lesser General Public License
38  * along with this package. If not, see <http://www.gnu.org/licenses/>.
39  ****************************************************************/
40 
41 #include <stdint.h>
42 typedef unsigned char uint8_t;
43 #include <inttypes.h>
44 #include <iostream>
45 #include <ros/ros.h>
47 
48 #include <std_srvs/Trigger.h>
49 
50 #include <math.h>
51 #include <iostream>
52 #define PI 3.14159265
53 
55 {
56 public:
58 
59  bool initFts();
60  bool srvCallback_SetBaudRate(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
61  bool srvCallback_SetBaseIdentifier(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
62  bool srvCallback_Reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
63  // create a handle for this node, initialize node
65 
66 private:
67  // CAN parameters
68  int canType;
69  std::string canPath;
71  int ftsBaseID;
74 
75  // service servers
79 
82 };
83 
85 {
86  m_isInitialized = false;
87 
92 
93  // Read data from parameter server
94  nh_.param<int>("HWComm/type", canType, -1);
95  nh_.param<std::string>("HWComm/path", canPath, "");
96  nh_.param<int>("HWComm/baudrate", canBaudrate, -1);
97  nh_.param<int>("FTS/base_identifier", ftsBaseID, -1);
98  nh_.param<int>("FTS/future_baudrate", ftsFutureBaudrate, 7);
99  nh_.param<int>("FTS/future_base_id", ftsFutureBaseID, 0x20);
100 
101  if (canType != -1)
102  {
103  p_Ftc = new ForceTorqueCtrl(canType, canPath, canBaudrate, ftsBaseID);
104  }
105  else
106  {
107  p_Ftc = new ForceTorqueCtrl();
108  }
109 
110  initFts();
111 }
112 
114 {
115  if (!m_isInitialized)
116  {
117  // read return init status and check it!
118  if (p_Ftc->Init())
119  {
120  ROS_INFO("FTC initialized");
121  m_isInitialized = true;
122  }
123  else
124  {
125  m_isInitialized = false;
126  ROS_INFO("FTC initialisation failed");
127  }
128  }
129  return m_isInitialized;
130 }
131 
132 bool ForceTorqueConfig::srvCallback_SetBaudRate(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
133 {
134  if (m_isInitialized)
135  {
137  {
138  ROS_INFO("New baud rate successfully set to: %d", ftsFutureBaudrate);
139 
140  res.success = true;
141  res.message = "All good, you are nice person! :)";
142  }
143  else
144  {
145  res.success = false;
146  res.message = "Could not set baud rate :)";
147  }
148  }
149  else
150  {
151  res.success = false;
152  res.message = "FTS not initialised! :/";
153  }
154 
155  return true;
156 }
157 
158 bool ForceTorqueConfig::srvCallback_SetBaseIdentifier(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
159 {
160  if (m_isInitialized)
161  {
163  {
164  ROS_INFO("New base identifier successfully set to HEX: %x", ftsFutureBaseID);
165 
166  res.success = true;
167  res.message = "All good, you are nice person! :)";
168  }
169  else
170  {
171  res.success = false;
172  res.message = "Could not set base identifier :)";
173  }
174  }
175  else
176  {
177  res.success = false;
178  res.message = "FTS not initialised! :/";
179  }
180 
181  return true;
182 }
183 
184 bool ForceTorqueConfig::srvCallback_Reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
185 {
186  ROS_WARN("Going to reset NETCANOEM!");
187 
188  if (p_Ftc->Reset())
189  {
190  res.success = true;
191  res.message = "Reset succeded!";
192  }
193  else
194  {
195  res.success = false;
196  res.message = "Reset NOT succeded!";
197  }
198 
199  return true;
200 }
201 
202 int main(int argc, char **argv)
203 {
204  ros::init(argc, argv, "forcetorque_config");
205  ForceTorqueConfig ftn;
206 
207  ROS_INFO("ForceTorque Config Node running.");
208 
209  ros::spin();
210 
211  return 0;
212 }
ros::ServiceServer srvServer_SetBaseIdentifier_
bool srvCallback_Reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
ros::ServiceServer srvServer_SetBaudRate_
ROSCPP_DECL void spin(Spinner &spinner)
bool SetBaudRate(int value)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool SetBaseIdentifier(int identifier)
ros::ServiceServer srvSever_Reset_
unsigned char uint8_t
bool srvCallback_SetBaudRate(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
bool srvCallback_SetBaseIdentifier(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
int main(int argc, char **argv)


ati_force_torque
Author(s): Denis Štogl, Alexander Bubeck
autogenerated on Thu Sep 17 2020 03:18:35