18 #include <mavros_msgs/RCOut.h>
19 #include <sensor_msgs/JointState.h>
49 int min_,
int max_,
int trim_,
int dz_,
68 pwm = std::max(pwm,
rc_min);
69 pwm = std::min(pwm,
rc_max);
86 if (!std::isfinite(chan)) {
119 ROS_INFO(
"SSP: URDF robot: %s", model.getName().c_str());
121 for (
auto &pair : param_dict) {
122 ROS_DEBUG(
"SSP: Loading joint: %s", pair.first.c_str());
128 int rc_channel, rc_min, rc_max, rc_trim, rc_dz;
130 if (!pnh.
getParam(
"rc_channel", rc_channel)) {
131 ROS_ERROR(
"SSP: '%s' should provice rc_channel", pair.first.c_str());
135 pnh.
param(
"rc_min", rc_min, 1000);
136 pnh.
param(
"rc_max", rc_max, 2000);
137 if (!pnh.
getParam(
"rc_trim", rc_trim)) {
138 rc_trim = rc_min + (rc_max - rc_min) / 2;
141 pnh.
param(
"rc_dz", rc_dz, 0);
142 pnh.
param(
"rc_rev", rc_rev,
false);
144 auto joint = model.getJoint(pair.first);
146 ROS_ERROR(
"SSP: URDF: there no joint '%s'", pair.first.c_str());
149 if (!joint->limits) {
150 ROS_ERROR(
"SSP: URDF: joint '%s' should provide <limit>", pair.first.c_str());
154 double lower = joint->limits->lower;
155 double upper = joint->limits->upper;
157 servos.emplace_back(pair.first,
lower,
upper, rc_channel, rc_min, rc_max, rc_trim, rc_dz, rc_rev);
158 ROS_INFO(
"SSP: joint '%s' (RC%d) loaded", pair.first.c_str(), rc_channel);
167 ROS_WARN(
"SSP: there nothing to do, exiting");
171 ROS_INFO(
"SSP: Initialization done. %zu joints served",
servos.size());
183 if (
msg->channels.empty())
186 auto states = boost::make_shared<sensor_msgs::JointState>();
187 states->header.stamp =
msg->header.stamp;
189 for (
auto &desc :
servos) {
190 if (!(desc.rc_channel != 0 && desc.rc_channel <=
msg->channels.size()))
193 uint16_t pwm =
msg->channels[desc.rc_channel - 1];
194 if (pwm == 0 || pwm == UINT16_MAX)
197 states->name.emplace_back(desc.joint_name);
198 states->position.emplace_back(desc.calculate_position(pwm));
205 int main(
int argc,
char *argv[])
207 ros::init(argc, argv,
"servo_state_publisher");
210 state_publisher.
spin();