YouBotJoint.hpp
Go to the documentation of this file.
1 #ifndef YOUBOT_YOUBOTJOINT_H
2 #define YOUBOT_YOUBOTJOINT_H
3 
4 /****************************************************************
5  *
6  * Copyright (c) 2011
7  * All rights reserved.
8  *
9  * Hochschule Bonn-Rhein-Sieg
10  * University of Applied Sciences
11  * Computer Science Department
12  *
13  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
14  *
15  * Author:
16  * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov
17  * Supervised by:
18  * Gerhard K. Kraetzschmar
19  *
20  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
21  *
22  * This sofware is published under a dual-license: GNU Lesser General Public
23  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
24  * code may choose which terms they prefer.
25  *
26  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
27  *
28  * Redistribution and use in source and binary forms, with or without
29  * modification, are permitted provided that the following conditions are met:
30  *
31  * * Redistributions of source code must retain the above copyright
32  * notice, this list of conditions and the following disclaimer.
33  * * Redistributions in binary form must reproduce the above copyright
34  * notice, this list of conditions and the following disclaimer in the
35  * documentation and/or other materials provided with the distribution.
36  * * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its
37  * contributors may be used to endorse or promote products derived from
38  * this software without specific prior written permission.
39  *
40  * This program is free software: you can redistribute it and/or modify
41  * it under the terms of the GNU Lesser General Public License LGPL as
42  * published by the Free Software Foundation, either version 2.1 of the
43  * License, or (at your option) any later version or the BSD license.
44  *
45  * This program is distributed in the hope that it will be useful,
46  * but WITHOUT ANY WARRANTY; without even the implied warranty of
47  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
48  * GNU Lesser General Public License LGPL and the BSD license for more details.
49  *
50  * You should have received a copy of the GNU Lesser General Public
51  * License LGPL and BSD license along with this program.
52  *
53  ****************************************************************/
54 #include <vector>
55 #include <sstream>
56 #include <cmath>
57 #include <boost/thread.hpp>
58 #include <boost/scoped_ptr.hpp>
70 
71 namespace youbot {
72 
77 class YouBotJoint : public Joint {
78  public:
79  YouBotJoint(const unsigned int jointNo, const std::string& configFilePath = "../config/");
80 
81  ~YouBotJoint();
82 
83 
84  private:
85  YouBotJoint(const YouBotJoint & source);
86 
87  YouBotJoint & operator=(const YouBotJoint & source);
88 
89 
90  protected:
91  virtual void setConfigurationParameter(const JointParameter& parameter);
92 
93  virtual void getConfigurationParameter(JointParameter& parameter);
94 
95 
96  public:
98 
99  virtual void getConfigurationParameter(YouBotJointParameter& parameter);
100 
101  virtual void setConfigurationParameter(const YouBotJointParameter& parameter);
102 
103  virtual void getConfigurationParameter(JointName& parameter);
104 
105  virtual void setConfigurationParameter(const JointName& parameter);
106 
107  virtual void getConfigurationParameter(GearRatio& parameter);
108 
109  virtual void setConfigurationParameter(const GearRatio& parameter);
110 
111  virtual void getConfigurationParameter(EncoderTicksPerRound& parameter);
112 
113  virtual void setConfigurationParameter(const EncoderTicksPerRound& parameter);
114 
115  virtual void setConfigurationParameter(const CalibrateJoint& parameter);
116 
117  virtual void setConfigurationParameter(const InverseMovementDirection& parameter);
118 
119  virtual void getConfigurationParameter(InverseMovementDirection& parameter);
120 
121  virtual void setConfigurationParameter(const JointLimits& parameter);
122 
123  virtual void getConfigurationParameter(JointLimits& parameter);
124 
125  virtual void getConfigurationParameter(JointLimitsRadian& parameter);
126 
128  virtual void setConfigurationParameter(const InitializeJoint& parameter);
129 
130  virtual void getConfigurationParameter(FirmwareVersion& parameter);
131 
133  virtual void setConfigurationParameter(const YouBotSlaveMailboxMsg& parameter);
134 
136  virtual void getConfigurationParameter(YouBotSlaveMailboxMsg& parameter);
137 
138  virtual void getConfigurationParameter(TorqueConstant& parameter);
139 
140  virtual void setConfigurationParameter(const TorqueConstant& parameter);
141 
145 
148 
149 
150  protected:
151  virtual void setData(const JointDataSetpoint& data);
152 
153  virtual void getData(JointData& data);
154 
155 
156  public:
159  virtual void setData(const JointAngleSetpoint& data);
160 
163  virtual void setData(const JointEncoderSetpoint& data);
164 
167  virtual void getData(JointSensedAngle& data);
168 
171  virtual void setData(const JointVelocitySetpoint& data);
172 
175  virtual void getData(JointSensedVelocity& data);
176 
179  virtual void getData(JointSensedRoundsPerMinute& data);
180 
183  virtual void setData(const JointRoundsPerMinuteSetpoint& data);
184 
187  virtual void getData(JointSensedCurrent& data);
188 
191  virtual void setData(const JointCurrentSetpoint& data);
192 
195  virtual void getData(JointSensedEncoderTicks& data);
196 
200  virtual void setData(const SlaveMessageOutput& data);
201 
205  virtual void getData(YouBotSlaveMsg& data);
206 
209  virtual void setData(const JointTorqueSetpoint& data);
210 
213  virtual void getData(JointSensedTorque& data);
214 
217  virtual void getData(JointAngleSetpoint& data);
218 
221  virtual void getData(JointVelocitySetpoint& data);
222 
225  virtual void getData(JointCurrentSetpoint& data);
226 
229  virtual void getData(JointRampGeneratorVelocity& data);
230 
231  void getUserVariable(const unsigned int index, int& data);
232 
233  void setUserVariable(const unsigned int index, const int data);
234 
236  virtual void getStatus(std::vector<std::string>& statusMessages);
237 
257  virtual void getStatus(unsigned int& statusFlags);
258 
260  void setEncoderToZero();
261 
262  void noMoreAction();
263 
264  void stopJoint();
265 
266  unsigned int getJointNumber();
267 
268 
269  private:
271 
272  void parseMailboxStatusFlags(const YouBotSlaveMailboxMsg& mailboxMsg);
273 
275 
276  bool setValueToMotorContoller(const YouBotSlaveMailboxMsg& mailboxMsg);
277 
278 
279  public:
281 
282 
283  private:
285 
287 
289 
290  unsigned int mailboxMsgRetries;
291 
293 
295 
296  quantity<si::angular_velocity> lastVelocity;
297 
298  quantity<plane_angle> lastPosition;
299 
300  boost::scoped_ptr<JointLimitMonitor> limitMonitor;
301 
302 };
303 
304 } // namespace youbot
305 #endif
EthercatMasterInterface * ethercatMaster
the firmware version of the joint
void parseMailboxStatusFlags(const YouBotSlaveMailboxMsg &mailboxMsg)
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
virtual void getConfigurationParameter(JointParameter &parameter)
Definition: YouBotJoint.cpp:83
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
bool retrieveValueFromMotorContoller(YouBotSlaveMailboxMsg &message)
YouBotSlaveMsg messageBuffer
Sensed encoder ticks of the joint.
Definition: JointData.hpp:100
abstract joint
Definition: Joint.hpp:63
unsigned int mailboxMsgRetries
Set-point velocity of the joint.
Definition: JointData.hpp:182
The torque set-point of the joint will be set by setting the computed current set-point.
Definition: JointData.hpp:218
JointTrajectoryController trajectoryController
quantity< si::angular_velocity > lastVelocity
Output part from the EtherCat message of the youBot EtherCat slaves.
virtual void setData(const JointDataSetpoint &data)
joint position limits in encoder ticks
void getUserVariable(const unsigned int index, int &data)
virtual void setConfigurationParameter(const JointParameter &parameter)
Definition: YouBotJoint.cpp:77
void parseYouBotErrorFlags(const YouBotSlaveMsg &messageBuffer)
This torque of the joint is computed from the actual current.
Definition: JointData.hpp:148
void storeConfigurationParameterPermanent(const YouBotJointParameter &parameter)
joint position limits in radian
Sensed velocity of the joint.
Definition: JointData.hpp:259
the name of the joint
unsigned int getJointNumber()
unsigned int timeTillNextMailboxUpdate
Sensed rounds per minute (rpm) of the joint.
Definition: JointData.hpp:124
the gear ratio which is needed for the calculations in the youBot driver
Sensed electric current of the joint.
Definition: JointData.hpp:136
encoder ticks setpoint of the joint
Definition: JointData.hpp:242
YouBotJointStorage storage
EtherCAT mailbox message of the youBot slaves.
abstract youBot joint parameter
abstract joint parameter
inverse the joint movement direction
The Ethercat Master interface.
void setUserVariable(const unsigned int index, const int data)
YouBotJoint & operator=(const YouBotJoint &source)
bool setValueToMotorContoller(const YouBotSlaveMailboxMsg &mailboxMsg)
quantity< plane_angle > lastPosition
virtual void getStatus(std::vector< std::string > &statusMessages)
Returns the status messages for the motor controller.
abstract data class for commanded joint data
Definition: JointData.hpp:160
void restoreConfigurationParameter(YouBotJointParameter &parameter)
Restores the joint parameter from the EEPROM.
Set-point current of the joint.
Definition: JointData.hpp:206
boost::scoped_ptr< JointLimitMonitor > limitMonitor
abstract youBot joint parameter which can be read only
virtual void getData(JointData &data)
void setEncoderToZero()
set the encoder values of the joint to zero. This postion will be the new reference.
Stores YouBotJoint informations which are needed in the driver.
abstract data class for joints
Definition: JointData.hpp:61
EtherCat message of the youBot EtherCat slaves.
Sensed position / angle of the joint.
Definition: JointData.hpp:88
YouBotJoint(const unsigned int jointNo, const std::string &configFilePath="../config/")
Definition: YouBotJoint.cpp:55
Set-point angle / position of the joint.
Definition: JointData.hpp:170
Rounds per minute set-point of the joint.
Definition: JointData.hpp:194
Sensed velocity of the joint.
Definition: JointData.hpp:112


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Jun 10 2019 15:46:25