Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SRC-4962 Add command type to JointState & ActuatorCommand #114

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <vector>

#include <ros/ros.h>

#include <sr_robot_msgs/ControlType.h>

namespace ros_ethercat_model
{
Expand Down Expand Up @@ -95,12 +95,17 @@ class ActuatorCommand
public:
ActuatorCommand() :
enable_(0),
effort_(0)
effort_(0),
// Initial value is neither FORCE not PWM to indicate that controller didn't set it yet
type_(sr_robot_msgs::ControlType::QUERY)
{
}

bool enable_; //!< Enable this actuator
double effort_; //!< Force to apply (in Nm)
double effort_; //!< Torque to apply (in Nm) or PWM value

/// Indicates if effort_ is torque or PWM
sr_robot_msgs::ControlType::_control_type_type type_;
};

/*!
Expand Down
6 changes: 6 additions & 0 deletions ros_ethercat_model/include/ros_ethercat_model/joint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <limits>
#include <tinyxml.h>
#include <urdf_model/joint.h>
#include <sr_robot_msgs/ControlType.h>

namespace ros_ethercat_model
{
Expand Down Expand Up @@ -167,6 +168,9 @@ class JointState
/// The effort the joint should apply in Nm or N (write-to variable)
double commanded_effort_;

/// Indicates if commanded_effort_ is torque or PWM
sr_robot_msgs::ControlType::_control_type_type actuator_command_type_;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I kind of dislike making the field a ROS msg when none of the others are...
I can't give a good reason for it though.
I guess storing the type could be done with an int enum, while a ROS msg class actually involves a much bigger object, with serialization methods and so on.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@toliver so you concur with introducing a enum for PWM/TORQUE within the generic ros_ethercat ? What if some other systems want CURRENT (in case they control their efforts in current or so) ?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_control_type_type is actually an alias for int enum. But I agree ideally we should get rid of existing dependency to sr_robot_msgs not add more usages.

Which one would you prefer locally declared enum with values: unspecified, torque, pwm or std::string with suggested values: "", "torque", "pwm" but allowing anything controller wants to pass to the driver?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@guihomework thanks for suggestion at top level comment. We should be able to add desired field in child classes at sr_core repository instead of here.


/// The position of the optical flag that was used to calibrate this joint
double reference_position_;

Expand All @@ -178,6 +182,8 @@ class JointState
commanded_position_(0.0),
commanded_velocity_(0.0),
commanded_effort_(0.0),
// Initial value is neither FORCE not PWM to indicate that controller didn't set it yet
actuator_command_type_(sr_robot_msgs::ControlType::QUERY),
reference_position_(0.0)
{
}
Expand Down