Fix several coverity issues:

* CID 350617: Dereference after null check
* CID 350585: Out-of-bounds read
* CID 350624: Resource leak
* CID 332701: Uncaught exception
* CID 350642: Uninitialized scalar field
* CID 350590: Uninitialized scalar field
* CID 350629: Uninitialized scalar variable
* CID 350602: Uninitialized scalar variable
* CID 350564: Uninitialized scalar variable
* CID 350548: Uninitialized scalar variable
This commit is contained in:
wmayer
2022-03-13 12:12:49 +01:00
parent 02bd57ac82
commit 68b92c504f
11 changed files with 85 additions and 58 deletions

View File

@@ -371,7 +371,6 @@ void PartGui::DlgProjectionOnSurface::store_current_selected_parts(std::vector<S
auto parentShape = currentShapeStore.inputShape;
for (auto itName = selObj.front().getSubNames().begin(); itName != selObj.front().getSubNames().end(); ++itName)
{
std::string parentName = aPart->getNameInDocument();
auto currentShape = aPart->Shape.getShape().getSubShape(itName->c_str());
transform_shape_to_global_position(currentShape, aPart);

View File

@@ -89,11 +89,11 @@ private:
std::vector<TopoDS_Wire> aProjectedWireInParametricSpaceVec;
TopoDS_Face aProjectedFace;
TopoDS_Shape aProjectedSolid;
Part::Feature* partFeature;
Part::Feature* partFeature = nullptr;
std::string partName;
bool is_selectable;
long transparency;
float exrudeValue;
bool is_selectable = false;
long transparency = 0;
float exrudeValue = 0.0f;
};
//from Gui::SelectionObserver

View File

@@ -137,18 +137,21 @@ void Robot6Axis::readKinematic(const char * FileName)
{
char buf[120];
std::ifstream in(FileName);
if(!in)return;
if (!in)
return;
std::vector<std::string> destination;
AxisDefinition temp[6];
// over read the header
in.getline(buf,119,'\n');
// read 6 Axis
for( int i = 0; i<6; i++){
for (int i = 0; i < 6; i++) {
in.getline(buf,79,'\n');
destination.clear();
split(std::string(buf),',',destination);
if(destination.size() < 8) continue;
if (destination.size() < 8)
continue;
// transfer the values in kinematic structure
temp[i].a = atof(destination[0].c_str());
temp[i].alpha = atof(destination[1].c_str());

View File

@@ -23,26 +23,27 @@
#ifndef ROBOT_ROBOT6AXLE_H
#define ROBOT_ROBOT6AXLE_H
#include "kdl_cp/chain.hpp"
#include "kdl_cp/jntarray.hpp"
#include <Base/Persistence.h>
#include <Base/Placement.h>
#include <Mod/Robot/RobotGlobal.h>
namespace Robot
{
/// Definition of the Axis properties
struct AxisDefinition {
double a; // a of the Denavit-Hartenberg parameters (mm)
double alpha; // alpha of the Denavit-Hartenberg parameters (°)
double d; // d of the Denavit-Hartenberg parameters (mm)
double theta; // a of the Denavit-Hartenberg parameters (°)
double rotDir; // rotational direction (1|-1)
double maxAngle; // soft ends + in °
double minAngle; // soft ends - in °
double velocity; // max vlocity of the axle in °/s
double a = 0.0; // a of the Denavit-Hartenberg parameters (mm)
double alpha = 0.0; // alpha of the Denavit-Hartenberg parameters (°)
double d = 0.0; // d of the Denavit-Hartenberg parameters (mm)
double theta = 0.0; // a of the Denavit-Hartenberg parameters (°)
double rotDir = 0.0; // rotational direction (1|-1)
double maxAngle = 0.0; // soft ends + in °
double minAngle = 0.0; // soft ends - in °
double velocity = 0.0; // max vlocity of the axle in °/s
};
@@ -56,40 +57,39 @@ public:
Robot6Axis();
~Robot6Axis();
// from base class
// from base class
virtual unsigned int getMemSize (void) const;
virtual void Save (Base::Writer &/*writer*/) const;
virtual void Save (Base::Writer &/*writer*/) const;
virtual void Restore(Base::XMLReader &/*reader*/);
// interface
// interface
/// set the kinematic parameters of the robot
void setKinematic(const AxisDefinition KinDef[6]);
/// read the kinematic parameters of the robot from a file
void readKinematic(const char * FileName);
/// set the robot to that position, calculates the Axis
bool setTo(const Base::Placement &To);
bool setAxis(int Axis,double Value);
double getAxis(int Axis);
bool setTo(const Base::Placement &To);
bool setAxis(int Axis,double Value);
double getAxis(int Axis);
double getMaxAngle(int Axis);
double getMinAngle(int Axis);
/// calculate the new Tcp out of the Axis
bool calcTcp(void);
Base::Placement getTcp(void);
/// calculate the new Tcp out of the Axis
bool calcTcp(void);
Base::Placement getTcp(void);
//void setKinematik(const std::vector<std::vector<float> > &KinTable);
protected:
KDL::Chain Kinematic;
KDL::JntArray Actuall;
KDL::JntArray Min;
KDL::JntArray Max;
KDL::Frame Tcp;
double Velocity[6];
double RotDir [6];
KDL::Chain Kinematic;
KDL::JntArray Actuall;
KDL::JntArray Min;
KDL::JntArray Max;
KDL::Frame Tcp;
double Velocity[6];
double RotDir [6];
};
} //namespace Part