robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
impact_status.hpp
Go to the documentation of this file.
1#ifndef ROBOTOC_IMPACT_STATUS_HPP_
2#define ROBOTOC_IMPACT_STATUS_HPP_
3
4#include <vector>
5#include <iostream>
6
7#include "Eigen/Core"
8
10#include "robotoc/robot/se3.hpp"
12
13
14namespace robotoc {
15
22public:
30 ImpactStatus(const std::vector<ContactType>& contact_types,
31 const std::vector<std::string>& contact_frame_names,
32 const double default_friction_coefficient=0.7);
33
38
42 ~ImpactStatus() = default;
43
47 ImpactStatus(const ImpactStatus&) = default;
48
53
57 ImpactStatus(ImpactStatus&&) noexcept = default;
58
62 ImpactStatus& operator=(ImpactStatus&&) noexcept = default;
63
67 bool operator==(const ImpactStatus& other) const;
68
72 bool operator!=(const ImpactStatus& other) const;
73
79 ContactType contactType(const int contact_index) const;
80
85 const std::vector<ContactType>& contactTypes() const;
86
92 bool isImpactActive(const int contact_index) const;
93
98 const std::vector<bool>& isImpactActive() const;
99
104 bool hasActiveImpact() const;
105
110 int dimf() const;
111
116 int maxNumContacts() const;
117
122 void activateImpact(const int contact_index);
123
128 void deactivateImpact(const int contact_index);
129
134 void activateImpacts(const std::vector<int>& impact_indices);
135
140 void deactivateImpacts(const std::vector<int>& impact_indices);
141
152 void setContactPlacement(const int contact_index,
153 const Eigen::Vector3d& contact_position);
154
165 void setContactPlacement(const int contact_index,
166 const Eigen::Vector3d& contact_position,
167 const Eigen::Matrix3d& contact_rotation);
168
178 void setContactPlacement(const int contact_index,
179 const SE3& contact_placement);
180
189 const std::vector<Eigen::Vector3d>& contact_positions);
190
199 const std::vector<Eigen::Vector3d>& contact_positions,
200 const std::vector<Eigen::Matrix3d>& contact_rotations);
201
207 void setContactPlacements(const aligned_vector<SE3>& contact_placements);
208
214 const SE3& contactPlacement(const int contact_index) const;
215
221 const Eigen::Vector3d& contactPosition(const int contact_index) const;
222
228 const Eigen::Matrix3d& contactRotation(const int contact_index) const;
229
234 const aligned_vector<SE3>& contactPlacements() const;
235
240 const std::vector<Eigen::Vector3d>& contactPositions() const;
241
246 const std::vector<Eigen::Matrix3d>& contactRotations() const;
247
253 void setFrictionCoefficient(const int contact_index,
254 const double friction_coefficient);
255
261 void setFrictionCoefficient(const std::string& contact_frame_name,
262 const double friction_coefficient);
263
269 void setFrictionCoefficients(const std::vector<double>& friction_coefficients);
270
277 const std::unordered_map<std::string, double>& friction_coefficients);
278
284 double frictionCoefficient(const int contact_index) const;
285
291 double frictionCoefficient(const std::string& contact_frame_name) const;
292
297 const std::vector<double>& frictionCoefficients() const;
298
302 void setRandom();
303
307 void disp(std::ostream& os) const;
308
309 friend std::ostream& operator<<(std::ostream& os,
310 const ImpactStatus& impact_status);
311
312private:
313 ContactStatus contact_status_;
314
315};
316
317} // namespace robotoc
318
319#include "robotoc/robot/impact_status.hxx"
320
321#endif // ROBOTOC_IMPACT_STATUS_HPP_
Contact status of robot model.
Definition: contact_status.hpp:32
Impact status of robot model. Wrapper of ContactStatus to treat impacts.
Definition: impact_status.hpp:21
const std::vector< Eigen::Matrix3d > & contactRotations() const
Gets the contact rotations.
Definition: impact_status.hxx:171
void setContactPlacement(const int contact_index, const Eigen::Vector3d &contact_position)
Sets a contact placement, that is, the position and rotation of the contact. The contact rotation is ...
Definition: impact_status.hxx:102
ImpactStatus()
Default constructor.
Definition: impact_status.hxx:21
ImpactStatus(ImpactStatus &&) noexcept=default
Default move constructor.
~ImpactStatus()=default
Default destructor.
ContactType contactType(const int contact_index) const
Returns the type of the contact.
Definition: impact_status.hxx:45
void setFrictionCoefficients(const std::vector< double > &friction_coefficients)
Sets the friction coefficints.
Definition: impact_status.hxx:188
void setContactPlacements(const std::vector< Eigen::Vector3d > &contact_positions)
Sets contact placements. The rotation of each contact is set to Eigen::Matrix3d::Identity(),...
Definition: impact_status.hxx:122
ImpactStatus(const ImpactStatus &)=default
Default copy constructor.
int dimf() const
Returns the dimension of the active impact forces.
Definition: impact_status.hxx:70
const SE3 & contactPlacement(const int contact_index) const
Gets the contact placement.
Definition: impact_status.hxx:141
ImpactStatus & operator=(const ImpactStatus &)=default
Default copy assign operator.
const std::vector< double > & frictionCoefficients() const
Gets the friction coefficints. Default value is 0.7.
Definition: impact_status.hxx:211
void setFrictionCoefficient(const int contact_index, const double friction_coefficient)
Gets the friction coefficint.
Definition: impact_status.hxx:176
void deactivateImpact(const int contact_index)
Deactivates a impact.
Definition: impact_status.hxx:85
double frictionCoefficient(const int contact_index) const
Gets the friction coefficint. Default value is 0.7.
Definition: impact_status.hxx:200
const std::vector< Eigen::Vector3d > & contactPositions() const
Gets the contact positions.
Definition: impact_status.hxx:165
void disp(std::ostream &os) const
Displays the impact status onto a ostream.
const std::vector< bool > & isImpactActive() const
Returns the activity of the impacts.
Definition: impact_status.hxx:60
const std::vector< ContactType > & contactTypes() const
Returns the types of the contacts.
Definition: impact_status.hxx:50
const Eigen::Matrix3d & contactRotation(const int contact_index) const
Gets the contact rotation.
Definition: impact_status.hxx:153
const aligned_vector< SE3 > & contactPlacements() const
Gets the contact placements.
Definition: impact_status.hxx:159
int maxNumContacts() const
Returns the maximum number of the contacts.
Definition: impact_status.hxx:75
void setRandom()
Fills impact status randomly.
Definition: impact_status.hxx:216
bool hasActiveImpact() const
Returns true if there are active impacts and false if not.
Definition: impact_status.hxx:65
void activateImpact(const int contact_index)
Activates a impact.
Definition: impact_status.hxx:80
void activateImpacts(const std::vector< int > &impact_indices)
Activates impacts.
Definition: impact_status.hxx:90
void deactivateImpacts(const std::vector< int > &impact_indices)
Deactivates impacts.
Definition: impact_status.hxx:96
const Eigen::Vector3d & contactPosition(const int contact_index) const
Gets the contact position.
Definition: impact_status.hxx:147
Definition: constraint_component_base.hpp:17
ContactType
Types of contacts.
Definition: contact_status.hpp:22
std::vector< T, Eigen::aligned_allocator< T > > aligned_vector
std vector with Eigen::aligned_allocator.
Definition: aligned_vector.hpp:14
pinocchio::SE3 SE3
Using pinocchio::SE3 without its namespace.
Definition: se3.hpp:15